mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
Copter: allow motor tests to be triggered with COMMAND_INT
This commit is contained in:
parent
a1b021e833
commit
5e9c2a04d0
@ -756,6 +756,9 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_int_packet(const mavlink_command_i
|
||||
case MAV_CMD_DO_PAUSE_CONTINUE:
|
||||
return handle_command_pause_continue(packet);
|
||||
|
||||
case MAV_CMD_DO_MOTOR_TEST:
|
||||
return handle_MAV_CMD_DO_MOTOR_TEST(packet);
|
||||
|
||||
#if AC_MAVLINK_SOLO_BUTTON_COMMAND_HANDLING_ENABLED
|
||||
// Solo user presses pause button
|
||||
case MAV_CMD_SOLO_BTN_PAUSE_CLICK:
|
||||
@ -915,7 +918,13 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_
|
||||
return MAV_RESULT_FAILED;
|
||||
#endif
|
||||
|
||||
case MAV_CMD_DO_MOTOR_TEST:
|
||||
default:
|
||||
return GCS_MAVLINK::handle_command_long_packet(packet, msg);
|
||||
}
|
||||
}
|
||||
|
||||
MAV_RESULT GCS_MAVLINK_Copter::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)
|
||||
@ -927,11 +936,7 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_
|
||||
(uint8_t)packet.param2,
|
||||
packet.param3,
|
||||
packet.param4,
|
||||
(uint8_t)packet.param5);
|
||||
|
||||
default:
|
||||
return GCS_MAVLINK::handle_command_long_packet(packet, msg);
|
||||
}
|
||||
(uint8_t)packet.x);
|
||||
}
|
||||
|
||||
#if AP_WINCH_ENABLED
|
||||
|
@ -98,6 +98,8 @@ private:
|
||||
#endif // HAL_HIGH_LATENCY2_ENABLED
|
||||
|
||||
|
||||
MAV_RESULT handle_MAV_CMD_DO_MOTOR_TEST(const mavlink_command_int_t &packet);
|
||||
|
||||
#if AC_MAVLINK_SOLO_BUTTON_COMMAND_HANDLING_ENABLED
|
||||
MAV_RESULT handle_MAV_CMD_SOLO_BTN_FLY_CLICK(const mavlink_command_int_t &packet);
|
||||
MAV_RESULT handle_MAV_CMD_SOLO_BTN_FLY_HOLD(const mavlink_command_int_t &packet);
|
||||
|
@ -3800,14 +3800,14 @@ class AutoTestCopter(AutoTest):
|
||||
self.disarm_vehicle(force=True)
|
||||
self.reboot_sitl()
|
||||
|
||||
def MotorTest(self, timeout=60):
|
||||
'''Run Motor Tests'''
|
||||
def _MotorTest(self, command, timeout=60):
|
||||
'''Run Motor Tests (with specific mavlink message)'''
|
||||
self.start_subtest("Testing PWM output")
|
||||
pwm_in = 1300
|
||||
# default frame is "+" - start motor of 2 is "B", which is
|
||||
# motor 1... see
|
||||
# https://ardupilot.org/copter/docs/connect-escs-and-motors.html
|
||||
self.run_cmd(
|
||||
command(
|
||||
mavutil.mavlink.MAV_CMD_DO_MOTOR_TEST,
|
||||
p1=2, # start motor
|
||||
p2=mavutil.mavlink.MOTOR_TEST_THROTTLE_PWM,
|
||||
@ -3829,7 +3829,7 @@ class AutoTestCopter(AutoTest):
|
||||
# min/max are used.
|
||||
expected_pwm = 1000 + (self.get_parameter("RC3_MAX") - self.get_parameter("RC3_MIN")) * percentage/100.0
|
||||
self.progress("expected pwm=%f" % expected_pwm)
|
||||
self.run_cmd(
|
||||
command(
|
||||
mavutil.mavlink.MAV_CMD_DO_MOTOR_TEST,
|
||||
p1=2, # start motor
|
||||
p2=mavutil.mavlink.MOTOR_TEST_THROTTLE_PERCENT,
|
||||
@ -3844,6 +3844,11 @@ class AutoTestCopter(AutoTest):
|
||||
self.wait_statustext("finished motor test")
|
||||
self.end_subtest("Testing percentage output")
|
||||
|
||||
def MotorTest(self, timeout=60):
|
||||
'''Run Motor Tests'''
|
||||
self._MotorTest(self.run_cmd)
|
||||
self._MotorTest(self.run_cmd_int)
|
||||
|
||||
def PrecisionLanding(self):
|
||||
"""Use PrecLand backends precision messages to land aircraft."""
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user