mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: provide and use base-method implementation for guided mode request
This commit is contained in:
parent
95661bb9bb
commit
f1457034e2
|
@ -1014,7 +1014,7 @@ private:
|
|||
|
||||
void send_distance_sensor(const class AP_RangeFinder_Backend *sensor, const uint8_t instance) const;
|
||||
|
||||
virtual bool handle_guided_request(AP_Mission::Mission_Command &cmd) = 0;
|
||||
virtual bool handle_guided_request(AP_Mission::Mission_Command &cmd) { return false; };
|
||||
virtual void handle_change_alt_request(AP_Mission::Mission_Command &cmd) {};
|
||||
void handle_common_mission_message(const mavlink_message_t &msg);
|
||||
|
||||
|
|
|
@ -25,7 +25,6 @@ private:
|
|||
|
||||
uint32_t telem_delay() const override { return 0; }
|
||||
bool try_send_message(enum ap_message id) override { return true; }
|
||||
bool handle_guided_request(AP_Mission::Mission_Command &cmd) override { return true; }
|
||||
uint8_t sysid_my_gcs() const override { return 1; }
|
||||
|
||||
protected:
|
||||
|
|
Loading…
Reference in New Issue