Copter: use visual odometry singleton

This commit is contained in:
Peter Barker 2018-04-06 18:03:30 +10:00 committed by Peter Barker
parent dbdf17d6c6
commit 0dce6172f2
2 changed files with 0 additions and 11 deletions

View File

@ -1324,16 +1324,6 @@ 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

@ -16,7 +16,6 @@ protected:
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;
uint8_t sysid_my_gcs() const override;
bool sysid_enforce() const override;