Plane: allow DO_VTOL_TRANSITION as both LONG and INT commands
This commit is contained in:
parent
cb2ea97f66
commit
ee316f04ed
@ -984,6 +984,11 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_packet(const mavlink_command_in
|
||||
case MAV_CMD_DO_CHANGE_SPEED:
|
||||
return handle_command_DO_CHANGE_SPEED(packet);
|
||||
|
||||
#if HAL_QUADPLANE_ENABLED
|
||||
case MAV_CMD_DO_VTOL_TRANSITION:
|
||||
return handle_command_DO_VTOL_TRANSITION(packet);
|
||||
#endif
|
||||
|
||||
default:
|
||||
return GCS_MAVLINK::handle_command_int_packet(packet, msg);
|
||||
}
|
||||
@ -1094,12 +1099,6 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_long_packet(const mavlink_command_l
|
||||
(uint16_t)packet.param3,
|
||||
packet.param4,
|
||||
(uint8_t)packet.param5);
|
||||
|
||||
case MAV_CMD_DO_VTOL_TRANSITION:
|
||||
if (!plane.quadplane.handle_do_vtol_transition((enum MAV_VTOL_STATE)packet.param1)) {
|
||||
return MAV_RESULT_FAILED;
|
||||
}
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
#endif
|
||||
|
||||
default:
|
||||
@ -1107,6 +1106,16 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_long_packet(const mavlink_command_l
|
||||
}
|
||||
}
|
||||
|
||||
#if HAL_QUADPLANE_ENABLED
|
||||
MAV_RESULT GCS_MAVLINK_Plane::handle_command_DO_VTOL_TRANSITION(const mavlink_command_int_t &packet)
|
||||
{
|
||||
if (!plane.quadplane.handle_do_vtol_transition((enum MAV_VTOL_STATE)packet.param1)) {
|
||||
return MAV_RESULT_FAILED;
|
||||
}
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
#endif
|
||||
|
||||
// this is called on receipt of a MANUAL_CONTROL packet and is
|
||||
// expected to call manual_override to override RC input on desired
|
||||
// axes.
|
||||
|
@ -55,6 +55,7 @@ private:
|
||||
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_DO_CHANGE_SPEED(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;
|
||||
void packetReceived(const mavlink_status_t &status, const mavlink_message_t &msg) override;
|
||||
|
Loading…
Reference in New Issue
Block a user