mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 14:48:28 -04:00
Plane: handle DO_PARACHUTE as both COMMAND_LONG and COMMAND_INT
This commit is contained in:
parent
2c44d75f27
commit
63c88fea58
@ -984,6 +984,11 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_packet(const mavlink_command_in
|
|||||||
case MAV_CMD_DO_CHANGE_SPEED:
|
case MAV_CMD_DO_CHANGE_SPEED:
|
||||||
return handle_command_DO_CHANGE_SPEED(packet);
|
return handle_command_DO_CHANGE_SPEED(packet);
|
||||||
|
|
||||||
|
#if PARACHUTE == ENABLED
|
||||||
|
case MAV_CMD_DO_PARACHUTE:
|
||||||
|
return handle_MAV_CMD_DO_PARACHUTE(packet);
|
||||||
|
#endif
|
||||||
|
|
||||||
#if HAL_QUADPLANE_ENABLED
|
#if HAL_QUADPLANE_ENABLED
|
||||||
case MAV_CMD_DO_MOTOR_TEST:
|
case MAV_CMD_DO_MOTOR_TEST:
|
||||||
return handle_MAV_CMD_DO_MOTOR_TEST(packet);
|
return handle_MAV_CMD_DO_MOTOR_TEST(packet);
|
||||||
@ -1059,8 +1064,14 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_long_packet(const mavlink_command_l
|
|||||||
plane.autotune_enable(!is_zero(packet.param1));
|
plane.autotune_enable(!is_zero(packet.param1));
|
||||||
return MAV_RESULT_ACCEPTED;
|
return MAV_RESULT_ACCEPTED;
|
||||||
|
|
||||||
|
default:
|
||||||
|
return GCS_MAVLINK::handle_command_long_packet(packet, msg);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
#if PARACHUTE == ENABLED
|
#if PARACHUTE == ENABLED
|
||||||
case MAV_CMD_DO_PARACHUTE:
|
MAV_RESULT GCS_MAVLINK_Plane::handle_MAV_CMD_DO_PARACHUTE(const mavlink_command_int_t &packet)
|
||||||
|
{
|
||||||
// configure or release parachute
|
// configure or release parachute
|
||||||
switch ((uint16_t)packet.param1) {
|
switch ((uint16_t)packet.param1) {
|
||||||
case PARACHUTE_DISABLE:
|
case PARACHUTE_DISABLE:
|
||||||
@ -1087,12 +1098,9 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_long_packet(const mavlink_command_l
|
|||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
return MAV_RESULT_FAILED;
|
return MAV_RESULT_FAILED;
|
||||||
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
default:
|
|
||||||
return GCS_MAVLINK::handle_command_long_packet(packet, msg);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
#if HAL_QUADPLANE_ENABLED
|
#if HAL_QUADPLANE_ENABLED
|
||||||
MAV_RESULT GCS_MAVLINK_Plane::handle_MAV_CMD_DO_MOTOR_TEST(const mavlink_command_int_t &packet)
|
MAV_RESULT GCS_MAVLINK_Plane::handle_MAV_CMD_DO_MOTOR_TEST(const mavlink_command_int_t &packet)
|
||||||
|
@ -56,6 +56,7 @@ private:
|
|||||||
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_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_command_DO_VTOL_TRANSITION(const mavlink_command_int_t &packet);
|
MAV_RESULT handle_command_DO_VTOL_TRANSITION(const mavlink_command_int_t &packet);
|
||||||
|
|
||||||
bool try_send_message(enum ap_message id) override;
|
bool try_send_message(enum ap_message id) override;
|
||||||
|
Loading…
Reference in New Issue
Block a user