APM:Libraries
AP_VisualOdom.h
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 #pragma once
16 
17 #include <AP_Common/AP_Common.h>
18 #include <AP_HAL/AP_HAL.h>
19 #include <AP_Param/AP_Param.h>
20 #include <AP_Math/AP_Math.h>
22 
24 
25 #define AP_VISUALODOM_TIMEOUT_MS 300
26 
28 {
29 public:
30  friend class AP_VisualOdom_Backend;
31 
32  AP_VisualOdom();
33 
34  // external position backend types (used by _TYPE parameter)
38  };
39 
40  // The VisualOdomState structure is filled in by the backend driver
41  struct VisualOdomState {
42  Vector3f angle_delta; // attitude delta (in radians) of most recent update
43  Vector3f position_delta; // position delta (in meters) of most recent update
44  uint64_t time_delta_usec; // time delta (in usec) between previous and most recent update
45  float confidence; // confidence expressed as a value from 0 (no confidence) to 100 (very confident)
46  uint32_t last_update_ms; // system time (in milliseconds) of last update from sensor
47  };
48 
49  // detect and initialise any sensors
50  void init();
51 
52  // return true if sensor is enabled
53  bool enabled() const;
54 
55  // return true if sensor is basically healthy (we are receiving data)
56  bool healthy() const;
57 
58  // state accessors
59  const Vector3f &get_angle_delta() const { return _state.angle_delta; }
60  const Vector3f &get_position_delta() const { return _state.position_delta; }
61  uint64_t get_time_delta_usec() const { return _state.time_delta_usec; }
62  float get_confidence() const { return _state.confidence; }
63  uint32_t get_last_update_ms() const { return _state.last_update_ms; }
64 
65  // return a 3D vector defining the position offset of the camera in meters relative to the body frame origin
66  const Vector3f &get_pos_offset(void) const { return _pos_offset; }
67 
68  // consume VISUAL_POSITION_DELTA data from MAVLink messages
69  void handle_msg(mavlink_message_t *msg);
70 
71  static const struct AP_Param::GroupInfo var_info[];
72 
73 private:
74 
75  // parameters
76  AP_Int8 _type;
77  AP_Vector3f _pos_offset; // position offset of the camera in the body frame
78  AP_Int8 _orientation; // camera orientation on vehicle frame
79 
80  // reference to backends
82 
83  // state of backend
85 };
bool healthy() const
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_VisualOdom.h:71
AP_Vector3f _pos_offset
Definition: AP_VisualOdom.h:77
const Vector3f & get_angle_delta() const
Definition: AP_VisualOdom.h:59
void handle_msg(mavlink_message_t *msg)
uint64_t get_time_delta_usec() const
Definition: AP_VisualOdom.h:61
A system for managing and storing variables that are of general interest to the system.
const Vector3f & get_position_delta() const
Definition: AP_VisualOdom.h:60
uint32_t get_last_update_ms() const
Definition: AP_VisualOdom.h:63
VisualOdomState _state
Definition: AP_VisualOdom.h:84
AP_VisualOdom_Backend * _driver
Definition: AP_VisualOdom.h:81
Common definitions and utility routines for the ArduPilot libraries.
AP_Int8 _orientation
Definition: AP_VisualOdom.h:78
bool enabled() const
float get_confidence() const
Definition: AP_VisualOdom.h:62
const Vector3f & get_pos_offset(void) const
Definition: AP_VisualOdom.h:66