mirror of https://github.com/ArduPilot/ardupilot
AP_VisualOdom: move from HAL_NO_GCS to HAL_GCS_ENABLED
This commit is contained in:
parent
4b5525f53e
commit
df3cfe12a9
|
@ -156,6 +156,7 @@ bool AP_VisualOdom::healthy() const
|
|||
return _driver->healthy();
|
||||
}
|
||||
|
||||
#if HAL_GCS_ENABLED
|
||||
// consume vision_position_delta mavlink messages
|
||||
void AP_VisualOdom::handle_vision_position_delta_msg(const mavlink_message_t &msg)
|
||||
{
|
||||
|
@ -169,6 +170,7 @@ void AP_VisualOdom::handle_vision_position_delta_msg(const mavlink_message_t &ms
|
|||
_driver->handle_vision_position_delta_msg(msg);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
// general purpose method to consume position estimate data and send to EKF
|
||||
// distances in meters, roll, pitch and yaw are in radians
|
||||
|
|
|
@ -27,6 +27,7 @@
|
|||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
|
||||
class AP_VisualOdom_Backend;
|
||||
|
||||
|
@ -80,8 +81,10 @@ public:
|
|||
// return yaw measurement noise in rad
|
||||
float get_yaw_noise() const { return _yaw_noise; }
|
||||
|
||||
#if HAL_GCS_ENABLED
|
||||
// consume vision_position_delta mavlink messages
|
||||
void handle_vision_position_delta_msg(const mavlink_message_t &msg);
|
||||
#endif
|
||||
|
||||
// general purpose methods to consume position estimate data and send to EKF
|
||||
// distances in meters, roll, pitch and yaw are in radians
|
||||
|
|
Loading…
Reference in New Issue