mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Sub: use camera singleton to get camera rather than callback
This commit is contained in:
parent
1aa75e4c3e
commit
753be1142f
@ -1259,15 +1259,6 @@ AP_Mission *GCS_MAVLINK_Sub::get_mission()
|
|||||||
return &sub.mission;
|
return &sub.mission;
|
||||||
}
|
}
|
||||||
|
|
||||||
AP_Camera *GCS_MAVLINK_Sub::get_camera() const
|
|
||||||
{
|
|
||||||
#if CAMERA == ENABLED
|
|
||||||
return &sub.camera;
|
|
||||||
#else
|
|
||||||
return nullptr;
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
|
|
||||||
AP_Rally *GCS_MAVLINK_Sub::get_rally() const
|
AP_Rally *GCS_MAVLINK_Sub::get_rally() const
|
||||||
{
|
{
|
||||||
#if AC_RALLY == ENABLED
|
#if AC_RALLY == ENABLED
|
||||||
|
@ -14,7 +14,6 @@ protected:
|
|||||||
|
|
||||||
AP_Mission *get_mission() override;
|
AP_Mission *get_mission() override;
|
||||||
AP_Rally *get_rally() const 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;
|
MAV_RESULT handle_flight_termination(const mavlink_command_long_t &packet) override;
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user