Rover: move handling of visual odometry messages up

This commit is contained in:
Peter Barker 2018-03-08 10:00:43 +11:00 committed by Randy Mackay
parent ed5140307a
commit 3c58eca0ab
5 changed files with 17 additions and 6 deletions

View File

@ -1359,10 +1359,6 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
rover.g2.proximity.handle_msg(msg);
break;
case MAVLINK_MSG_ID_VISION_POSITION_DELTA:
rover.g2.visual_odom.handle_msg(msg);
break;
default:
handle_common_message(msg);
break;
@ -1469,6 +1465,15 @@ AP_AdvancedFailsafe *GCS_MAVLINK_Rover::get_advanced_failsafe() const
#endif
}
AP_VisualOdom *GCS_MAVLINK_Rover::get_visual_odom() const
{
#if VISUAL_ODOMETRY_ENABLED == ENABLED
return &rover.g2.visual_odom;
#else
return nullptr;
#endif
}
Compass *GCS_MAVLINK_Rover::get_compass() const
{
return &rover.compass;

View File

@ -22,6 +22,7 @@ protected:
AP_Camera *get_camera() const override;
AP_ServoRelayEvents *get_servorelayevents() const override;
AP_AdvancedFailsafe *get_advanced_failsafe() const override;
AP_VisualOdom *get_visual_odom() const override;
const AP_FWVersion &get_fwver() const override;
void set_ekf_origin(const Location& loc) override;

View File

@ -96,6 +96,13 @@
#error XXX
#endif
//////////////////////////////////////////////////////////////////////////////
// VISUAL ODOMETRY
#ifndef VISUAL_ODOMETRY_ENABLED
# define VISUAL_ODOMETRY_ENABLED ENABLED
#endif
//////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////
// STARTUP BEHAVIOUR

View File

@ -42,7 +42,6 @@ LIBRARIES += AP_RPM
LIBRARIES += AP_Arming
LIBRARIES += AP_Stats
LIBRARIES += AP_Beacon
LIBRARIES += AP_VisualOdom
LIBRARIES += AP_WheelEncoder
LIBRARIES += AP_AdvancedFailsafe
LIBRARIES += AR_AttitudeControl

View File

@ -18,7 +18,6 @@ def build(bld):
'AC_PID',
'AP_Stats',
'AP_Beacon',
'AP_VisualOdom',
'AP_AdvancedFailsafe',
'AP_WheelEncoder',
'AP_SmartRTL',