mirror of https://github.com/ArduPilot/ardupilot
Plane: accept motor test as both command long and command int
This commit is contained in:
parent
164b7328bd
commit
06f1ac07bc
|
@ -985,6 +985,9 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_packet(const mavlink_command_in
|
|||
return handle_command_DO_CHANGE_SPEED(packet);
|
||||
|
||||
#if HAL_QUADPLANE_ENABLED
|
||||
case MAV_CMD_DO_MOTOR_TEST:
|
||||
return handle_MAV_CMD_DO_MOTOR_TEST(packet);
|
||||
|
||||
case MAV_CMD_DO_VTOL_TRANSITION:
|
||||
return handle_command_DO_VTOL_TRANSITION(packet);
|
||||
#endif
|
||||
|
@ -1086,8 +1089,14 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_long_packet(const mavlink_command_l
|
|||
return MAV_RESULT_FAILED;
|
||||
#endif
|
||||
|
||||
default:
|
||||
return GCS_MAVLINK::handle_command_long_packet(packet, msg);
|
||||
}
|
||||
}
|
||||
|
||||
#if HAL_QUADPLANE_ENABLED
|
||||
case MAV_CMD_DO_MOTOR_TEST:
|
||||
MAV_RESULT GCS_MAVLINK_Plane::handle_MAV_CMD_DO_MOTOR_TEST(const mavlink_command_int_t &packet)
|
||||
{
|
||||
// param1 : motor sequence number (a number from 1 to max number of motors on the vehicle)
|
||||
// param2 : throttle type (0=throttle percentage, 1=PWM, 2=pilot throttle channel pass-through. See MOTOR_TEST_THROTTLE_TYPE enum)
|
||||
// param3 : throttle (range depends upon param2)
|
||||
|
@ -1098,15 +1107,9 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_long_packet(const mavlink_command_l
|
|||
(uint8_t)packet.param2,
|
||||
(uint16_t)packet.param3,
|
||||
packet.param4,
|
||||
(uint8_t)packet.param5);
|
||||
#endif
|
||||
|
||||
default:
|
||||
return GCS_MAVLINK::handle_command_long_packet(packet, msg);
|
||||
}
|
||||
(uint8_t)packet.x);
|
||||
}
|
||||
|
||||
#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)) {
|
||||
|
|
|
@ -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_MAV_CMD_DO_MOTOR_TEST(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;
|
||||
|
|
Loading…
Reference in New Issue