Copter: move handling of visual odometry messages up

This commit is contained in:
Peter Barker 2018-03-08 09:52:48 +11:00 committed by Randy Mackay
parent 4f0cf6d334
commit 41960704b0
4 changed files with 11 additions and 8 deletions

View File

@ -1719,12 +1719,6 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
#endif
break;
case MAVLINK_MSG_ID_VISION_POSITION_DELTA:
#if VISUAL_ODOMETRY_ENABLED == ENABLED
copter.g2.visual_odom.handle_msg(msg);
#endif
break;
#if TOY_MODE_ENABLED == ENABLED
case MAVLINK_MSG_ID_NAMED_VALUE_INT:
copter.g2.toy_mode.handle_message(msg);
@ -1842,6 +1836,16 @@ AP_AdvancedFailsafe *GCS_MAVLINK_Copter::get_advanced_failsafe() const
#endif
}
AP_VisualOdom *GCS_MAVLINK_Copter::get_visual_odom() const
{
#if VISUAL_ODOMETRY_ENABLED == ENABLED
return &copter.g2.visual_odom;
#else
return nullptr;
#endif
}
MAV_RESULT GCS_MAVLINK_Copter::handle_flight_termination(const mavlink_command_long_t &packet) {
MAV_RESULT result = MAV_RESULT_FAILED;

View File

@ -25,6 +25,7 @@ protected:
AP_ServoRelayEvents *get_servorelayevents() const override;
MAV_RESULT handle_flight_termination(const mavlink_command_long_t &packet) 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

@ -62,7 +62,6 @@ LIBRARIES += AP_Stats
LIBRARIES += AP_Gripper
LIBRARIES += AP_Beacon
LIBRARIES += AP_Arming
LIBRARIES += AP_VisualOdom
LIBRARIES += AP_SmartRTL
LIBRARIES += AP_Winch
LIBRARIES += AP_WheelEncoder

View File

@ -32,7 +32,6 @@ def build(bld):
'AP_Gripper',
'AP_Beacon',
'AP_Arming',
'AP_VisualOdom',
'AP_WheelEncoder',
'AP_Winch',
'AP_Follow',