APM:Libraries
AP_VisualOdom.cpp
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 
16 #include "AP_VisualOdom.h"
17 #include "AP_VisualOdom_Backend.h"
18 #include "AP_VisualOdom_MAV.h"
19 
20 extern const AP_HAL::HAL &hal;
21 
22 // table of user settable parameters
24 
25  // @Param: _TYPE
26  // @DisplayName: Visual odometry camera connection type
27  // @Description: Visual odometry camera connection type
28  // @Values: 0:None,1:MAV
29  // @User: Advanced
30  AP_GROUPINFO("_TYPE", 0, AP_VisualOdom, _type, 0),
31 
32  // @Param: _POS_X
33  // @DisplayName: Visual odometry camera X position offset
34  // @Description: X position of the camera in body frame. Positive X is forward of the origin.
35  // @Units: m
36  // @User: Advanced
37 
38  // @Param: _POS_Y
39  // @DisplayName: Visual odometry camera Y position offset
40  // @Description: Y position of the camera in body frame. Positive Y is to the right of the origin.
41  // @Units: m
42  // @User: Advanced
43 
44  // @Param: _POS_Z
45  // @DisplayName: Visual odometry camera Z position offset
46  // @Description: Z position of the camera in body frame. Positive Z is down from the origin.
47  // @Units: m
48  // @User: Advanced
49  AP_GROUPINFO("_POS", 1, AP_VisualOdom, _pos_offset, 0.0f),
50 
51  // @Param: _ORIENT
52  // @DisplayName: Visual odometery camera orientation
53  // @Description: Visual odometery camera orientation
54  // @Values: 0:Forward, 2:Right, 4:Back, 6:Left, 24:Up, 25:Down
55  // @User: Advanced
56  AP_GROUPINFO("_ORIENT", 2, AP_VisualOdom, _orientation, ROTATION_NONE),
57 
59 };
60 
62 {
64 }
65 
66 // detect and initialise any sensors
68 {
69  // create backend
71  _driver = new AP_VisualOdom_MAV(*this);
72  }
73 }
74 
75 // return true if sensor is enabled
77 {
78  return ((_type != AP_VisualOdom_Type_None) && (_driver != nullptr));
79 }
80 
81 // return true if sensor is basically healthy (we are receiving data)
83 {
84  if (!enabled()) {
85  return false;
86  }
87 
88  // healthy if we have received sensor messages within the past 300ms
90 }
91 
92 // consume VISION_POSITION_DELTA MAVLink message
93 void AP_VisualOdom::handle_msg(mavlink_message_t *msg)
94 {
95  // exit immediately if not enabled
96  if (!enabled()) {
97  return;
98  }
99 
100  // call backend
101  if (_driver != nullptr) {
102  _driver->handle_msg(msg);
103  }
104 }
105 
virtual void handle_msg(mavlink_message_t *msg)
bool healthy() const
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_VisualOdom.h:71
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
void handle_msg(mavlink_message_t *msg)
#define f(i)
uint32_t millis()
Definition: system.cpp:157
VisualOdomState _state
Definition: AP_VisualOdom.h:84
AP_VisualOdom_Backend * _driver
Definition: AP_VisualOdom.h:81
#define AP_VISUALODOM_TIMEOUT_MS
Definition: AP_VisualOdom.h:25
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
bool enabled() const
#define AP_GROUPEND
Definition: AP_Param.h:121
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214