Copter: use camera singleton to get camera rather than callback

This commit is contained in:
Peter Barker 2018-08-30 21:01:58 +10:00 committed by Peter Barker
parent 3146fcd80a
commit f005ee4a4c
2 changed files with 0 additions and 10 deletions

View File

@ -1555,15 +1555,6 @@ AP_Mission *GCS_MAVLINK_Copter::get_mission()
#endif
}
AP_Camera *GCS_MAVLINK_Copter::get_camera() const
{
#if CAMERA == ENABLED
return &copter.camera;
#else
return nullptr;
#endif
}
AP_AdvancedFailsafe *GCS_MAVLINK_Copter::get_advanced_failsafe() const
{
#if ADVANCED_FAILSAFE == ENABLED

View File

@ -18,7 +18,6 @@ protected:
AP_Mission *get_mission() override;
AP_Rally *get_rally() const override;
AP_Camera *get_camera() 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;