mirror of https://github.com/ArduPilot/ardupilot
ArduCopter: provide default implemenation of handle_change_alt_request
The TODO items to actually implement these are almost 6 years old. Since then these methods have been burning space. This doesn't even make sense for several vehicles, so a default implementation which does nothing seems OK.
This commit is contained in:
parent
65ed077a4e
commit
4f2cf9ffa2
|
@ -559,16 +559,6 @@ bool GCS_MAVLINK_Copter::handle_guided_request(AP_Mission::Mission_Command &cmd)
|
|||
#endif
|
||||
}
|
||||
|
||||
void GCS_MAVLINK_Copter::handle_change_alt_request(AP_Mission::Mission_Command &cmd)
|
||||
{
|
||||
// add home alt if needed
|
||||
if (cmd.content.location.relative_alt) {
|
||||
cmd.content.location.alt += copter.ahrs.get_home().alt;
|
||||
}
|
||||
|
||||
// To-Do: update target altitude for loiter or waypoint controller depending upon nav mode
|
||||
}
|
||||
|
||||
void GCS_MAVLINK_Copter::packetReceived(const mavlink_status_t &status,
|
||||
const mavlink_message_t &msg)
|
||||
{
|
||||
|
|
|
@ -52,7 +52,6 @@ private:
|
|||
void handleMessage(const mavlink_message_t &msg) override;
|
||||
void handle_command_ack(const mavlink_message_t &msg) override;
|
||||
bool handle_guided_request(AP_Mission::Mission_Command &cmd) override;
|
||||
void handle_change_alt_request(AP_Mission::Mission_Command &cmd) override;
|
||||
bool try_send_message(enum ap_message id) override;
|
||||
|
||||
void packetReceived(const mavlink_status_t &status,
|
||||
|
|
Loading…
Reference in New Issue