mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-09 09:24:01 -04:00
GCS_MAVLink: use camera singleton to get camera rather than callback
This commit is contained in:
parent
e4c0ef789b
commit
26e7abe6c4
@ -254,7 +254,6 @@ protected:
|
||||
virtual bool accept_packet(const mavlink_status_t &status, mavlink_message_t &msg) { return true; }
|
||||
virtual AP_Mission *get_mission() = 0;
|
||||
virtual AP_Rally *get_rally() const = 0;
|
||||
virtual class AP_Camera *get_camera() const = 0;
|
||||
virtual AP_AdvancedFailsafe *get_advanced_failsafe() const { return nullptr; };
|
||||
virtual AP_VisualOdom *get_visual_odom() const { return nullptr; }
|
||||
virtual bool set_mode(uint8_t mode) = 0;
|
||||
|
@ -2023,7 +2023,7 @@ void GCS_MAVLINK::handle_system_time_message(const mavlink_message_t *msg)
|
||||
|
||||
MAV_RESULT GCS_MAVLINK::handle_command_camera(const mavlink_command_long_t &packet)
|
||||
{
|
||||
AP_Camera *camera = get_camera();
|
||||
AP_Camera *camera = AP::camera();
|
||||
if (camera == nullptr) {
|
||||
return MAV_RESULT_UNSUPPORTED;
|
||||
}
|
||||
@ -2316,7 +2316,7 @@ void GCS_MAVLINK::handle_common_message(mavlink_message_t *msg)
|
||||
|
||||
case MAVLINK_MSG_ID_DIGICAM_CONTROL:
|
||||
{
|
||||
AP_Camera *camera = get_camera();
|
||||
AP_Camera *camera = AP::camera();
|
||||
if (camera == nullptr) {
|
||||
return;
|
||||
}
|
||||
@ -3018,7 +3018,7 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
|
||||
|
||||
case MSG_CAMERA_FEEDBACK:
|
||||
{
|
||||
AP_Camera *camera = get_camera();
|
||||
AP_Camera *camera = AP::camera();
|
||||
if (camera == nullptr) {
|
||||
break;
|
||||
}
|
||||
|
@ -24,7 +24,6 @@ protected:
|
||||
|
||||
AP_Mission *get_mission() override { return nullptr; }
|
||||
AP_Rally *get_rally() const override { return nullptr; };
|
||||
AP_Camera *get_camera() const override { return nullptr; };
|
||||
|
||||
uint8_t sysid_my_gcs() const override { return 1; }
|
||||
bool set_mode(uint8_t mode) override { return false; };
|
||||
|
@ -30,7 +30,6 @@ protected:
|
||||
uint32_t telem_delay() const override { return 0; }
|
||||
AP_Mission *get_mission() override { return nullptr; }
|
||||
AP_Rally *get_rally() const override { return nullptr; }
|
||||
AP_Camera *get_camera() const override { return nullptr; };
|
||||
uint8_t sysid_my_gcs() const override { return 1; }
|
||||
bool set_mode(uint8_t mode) override { return false; };
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user