From 4e44ee1a07e5b665438c2a7d8343d792a2b9ed4c Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 24 Aug 2023 12:19:44 +1000 Subject: [PATCH] Rover: allow motor test to be issued as COMMAND_INT --- Rover/GCS_Mavlink.cpp | 22 +++++++++++----------- 1 file changed, 11 insertions(+), 11 deletions(-) diff --git a/Rover/GCS_Mavlink.cpp b/Rover/GCS_Mavlink.cpp index dc419cfcd3..ee268d7291 100644 --- a/Rover/GCS_Mavlink.cpp +++ b/Rover/GCS_Mavlink.cpp @@ -663,6 +663,17 @@ MAV_RESULT GCS_MAVLINK_Rover::handle_command_int_packet(const mavlink_command_in } return MAV_RESULT_FAILED; + case MAV_CMD_DO_MOTOR_TEST: + // 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) + // param4 : timeout (in seconds) + return rover.mavlink_motor_test_start(*this, + (AP_MotorsUGV::motor_test_order)packet.param1, + static_cast(packet.param2), + static_cast(packet.param3), + packet.param4); + default: return GCS_MAVLINK::handle_command_int_packet(packet, msg); } @@ -700,17 +711,6 @@ MAV_RESULT GCS_MAVLINK_Rover::handle_command_long_packet(const mavlink_command_l return MAV_RESULT_ACCEPTED; } - case MAV_CMD_DO_MOTOR_TEST: - // 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) - // param4 : timeout (in seconds) - return rover.mavlink_motor_test_start(*this, - (AP_MotorsUGV::motor_test_order)packet.param1, - static_cast(packet.param2), - static_cast(packet.param3), - packet.param4); - default: return GCS_MAVLINK::handle_command_long_packet(packet, msg); }