Rover: allow motor test to be issued as COMMAND_INT

This commit is contained in:
Peter Barker 2023-08-24 12:19:44 +10:00 committed by Peter Barker
parent 999919424b
commit 4e44ee1a07
1 changed files with 11 additions and 11 deletions

View File

@ -663,6 +663,17 @@ MAV_RESULT GCS_MAVLINK_Rover::handle_command_int_packet(const mavlink_command_in
} }
return MAV_RESULT_FAILED; 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<uint8_t>(packet.param2),
static_cast<int16_t>(packet.param3),
packet.param4);
default: default:
return GCS_MAVLINK::handle_command_int_packet(packet, msg); 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; 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<uint8_t>(packet.param2),
static_cast<int16_t>(packet.param3),
packet.param4);
default: default:
return GCS_MAVLINK::handle_command_long_packet(packet, msg); return GCS_MAVLINK::handle_command_long_packet(packet, msg);
} }