mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
Plane: accept MAV_CMD_DO_AUTOTUNE_ENABLE as both long and int
This commit is contained in:
parent
91f457d4eb
commit
11ffb059ae
@ -954,6 +954,9 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_packet(const mavlink_command_in
|
|||||||
{
|
{
|
||||||
switch(packet.command) {
|
switch(packet.command) {
|
||||||
|
|
||||||
|
case MAV_CMD_DO_AUTOTUNE_ENABLE:
|
||||||
|
return handle_MAV_CMD_DO_AUTOTUNE_ENABLE(packet);
|
||||||
|
|
||||||
case MAV_CMD_DO_REPOSITION:
|
case MAV_CMD_DO_REPOSITION:
|
||||||
return handle_command_int_do_reposition(packet);
|
return handle_command_int_do_reposition(packet);
|
||||||
|
|
||||||
@ -1059,16 +1062,18 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_long_packet(const mavlink_command_l
|
|||||||
case MAV_CMD_DO_GO_AROUND:
|
case MAV_CMD_DO_GO_AROUND:
|
||||||
return plane.trigger_land_abort(packet.param1) ? MAV_RESULT_ACCEPTED : MAV_RESULT_FAILED;
|
return plane.trigger_land_abort(packet.param1) ? MAV_RESULT_ACCEPTED : MAV_RESULT_FAILED;
|
||||||
|
|
||||||
case MAV_CMD_DO_AUTOTUNE_ENABLE:
|
|
||||||
// param1 : enable/disable
|
|
||||||
plane.autotune_enable(!is_zero(packet.param1));
|
|
||||||
return MAV_RESULT_ACCEPTED;
|
|
||||||
|
|
||||||
default:
|
default:
|
||||||
return GCS_MAVLINK::handle_command_long_packet(packet, msg);
|
return GCS_MAVLINK::handle_command_long_packet(packet, msg);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
MAV_RESULT GCS_MAVLINK_Plane::handle_MAV_CMD_DO_AUTOTUNE_ENABLE(const mavlink_command_int_t &packet)
|
||||||
|
{
|
||||||
|
// param1 : enable/disable
|
||||||
|
plane.autotune_enable(!is_zero(packet.param1));
|
||||||
|
return MAV_RESULT_ACCEPTED;
|
||||||
|
}
|
||||||
|
|
||||||
#if PARACHUTE == ENABLED
|
#if PARACHUTE == ENABLED
|
||||||
MAV_RESULT GCS_MAVLINK_Plane::handle_MAV_CMD_DO_PARACHUTE(const mavlink_command_int_t &packet)
|
MAV_RESULT GCS_MAVLINK_Plane::handle_MAV_CMD_DO_PARACHUTE(const mavlink_command_int_t &packet)
|
||||||
{
|
{
|
||||||
|
@ -54,6 +54,7 @@ private:
|
|||||||
void handle_change_alt_request(AP_Mission::Mission_Command &cmd) override;
|
void handle_change_alt_request(AP_Mission::Mission_Command &cmd) override;
|
||||||
MAV_RESULT handle_command_int_do_reposition(const mavlink_command_int_t &packet);
|
MAV_RESULT handle_command_int_do_reposition(const mavlink_command_int_t &packet);
|
||||||
MAV_RESULT handle_command_int_guided_slew_commands(const mavlink_command_int_t &packet);
|
MAV_RESULT handle_command_int_guided_slew_commands(const mavlink_command_int_t &packet);
|
||||||
|
MAV_RESULT handle_MAV_CMD_DO_AUTOTUNE_ENABLE(const mavlink_command_int_t &packet);
|
||||||
MAV_RESULT handle_command_DO_CHANGE_SPEED(const mavlink_command_int_t &packet);
|
MAV_RESULT handle_command_DO_CHANGE_SPEED(const mavlink_command_int_t &packet);
|
||||||
MAV_RESULT handle_MAV_CMD_DO_MOTOR_TEST(const mavlink_command_int_t &packet);
|
MAV_RESULT handle_MAV_CMD_DO_MOTOR_TEST(const mavlink_command_int_t &packet);
|
||||||
MAV_RESULT handle_MAV_CMD_DO_PARACHUTE(const mavlink_command_int_t &packet);
|
MAV_RESULT handle_MAV_CMD_DO_PARACHUTE(const mavlink_command_int_t &packet);
|
||||||
|
Loading…
Reference in New Issue
Block a user