AP_VisualOdom: correct compilation when HAL_GCS_ENABLED is false

This commit is contained in:
Peter Barker 2023-12-11 17:44:00 +11:00 committed by Andrew Tridgell
parent 93907f4a6d
commit 283a1edb9f
2 changed files with 4 additions and 0 deletions

View File

@ -36,6 +36,7 @@ bool AP_VisualOdom_Backend::healthy() const
return ((AP_HAL::millis() - _last_update_ms) < AP_VISUALODOM_TIMEOUT_MS); return ((AP_HAL::millis() - _last_update_ms) < AP_VISUALODOM_TIMEOUT_MS);
} }
#if HAL_GCS_ENABLED
// consume vision_position_delta mavlink messages // consume vision_position_delta mavlink messages
void AP_VisualOdom_Backend::handle_vision_position_delta_msg(const mavlink_message_t &msg) void AP_VisualOdom_Backend::handle_vision_position_delta_msg(const mavlink_message_t &msg)
{ {
@ -69,6 +70,7 @@ void AP_VisualOdom_Backend::handle_vision_position_delta_msg(const mavlink_messa
position_delta, position_delta,
packet.confidence); packet.confidence);
} }
#endif // HAL_GCS_ENABLED
// returns the system time of the last reset if reset_counter has not changed // returns the system time of the last reset if reset_counter has not changed
// updates the reset timestamp to the current system time if the reset_counter has changed // updates the reset timestamp to the current system time if the reset_counter has changed

View File

@ -27,8 +27,10 @@ public:
// return true if sensor is basically healthy (we are receiving data) // return true if sensor is basically healthy (we are receiving data)
bool healthy() const; bool healthy() const;
#if HAL_GCS_ENABLED
// consume vision_position_delta mavlink messages // consume vision_position_delta mavlink messages
void handle_vision_position_delta_msg(const mavlink_message_t &msg); void handle_vision_position_delta_msg(const mavlink_message_t &msg);
#endif
// consume vision pose estimate data and send to EKF. distances in meters // consume vision pose estimate data and send to EKF. distances in meters
virtual void handle_pose_estimate(uint64_t remote_time_us, uint32_t time_ms, float x, float y, float z, const Quaternion &attitude, float posErr, float angErr, uint8_t reset_counter) = 0; virtual void handle_pose_estimate(uint64_t remote_time_us, uint32_t time_ms, float x, float y, float z, const Quaternion &attitude, float posErr, float angErr, uint8_t reset_counter) = 0;