Rover: use visual odometry singleton

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

View File

@ -1114,15 +1114,6 @@ 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
}
bool GCS_MAVLINK_Rover::set_mode(const uint8_t mode)
{
Mode *new_mode = rover.mode_from_mode_num((enum Mode::Number)mode);

View File

@ -14,7 +14,6 @@ protected:
uint32_t telem_delay() const 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;