GCS_MAVLink: use AP_ServoRelayEvents singleton
This commit is contained in:
parent
544ac03ca6
commit
682679c68d
@ -231,7 +231,6 @@ protected:
|
||||
virtual AP_Rally *get_rally() const = 0;
|
||||
virtual Compass *get_compass() const = 0;
|
||||
virtual class AP_Camera *get_camera() const = 0;
|
||||
virtual AP_ServoRelayEvents *get_servorelayevents() 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;
|
||||
|
@ -27,7 +27,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; };
|
||||
AP_ServoRelayEvents *get_servorelayevents() const override { return nullptr; }
|
||||
const AP_FWVersion &get_fwver() const override { return fwver; }
|
||||
void set_ekf_origin(const Location& loc) override { };
|
||||
|
||||
|
@ -4,7 +4,7 @@
|
||||
|
||||
MAV_RESULT GCS_MAVLINK::handle_servorelay_message(mavlink_command_long_t &packet)
|
||||
{
|
||||
AP_ServoRelayEvents *handler = get_servorelayevents();
|
||||
AP_ServoRelayEvents *handler = AP::servorelayevents();
|
||||
if (handler == nullptr) {
|
||||
return MAV_RESULT_UNSUPPORTED;
|
||||
}
|
||||
|
@ -34,7 +34,6 @@ protected:
|
||||
Compass *get_compass() const override { return nullptr; };
|
||||
AP_Mission *get_mission() override { return nullptr; }
|
||||
AP_Rally *get_rally() const override { return nullptr; }
|
||||
AP_ServoRelayEvents *get_servorelayevents() 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