mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
autotest: augment relay tests to run as cmd_int, and more messages
This commit is contained in:
parent
b751224ae1
commit
d197ad6a90
@ -582,61 +582,105 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
|||||||
|
|
||||||
def ServoRelayEvents(self):
|
def ServoRelayEvents(self):
|
||||||
'''Test ServoRelayEvents'''
|
'''Test ServoRelayEvents'''
|
||||||
self.do_set_relay(0, 0)
|
for method in self.run_cmd, self.run_cmd_int:
|
||||||
off = self.get_parameter("SIM_PIN_MASK")
|
self.context_push()
|
||||||
self.do_set_relay(0, 1)
|
method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=0, p2=0)
|
||||||
on = self.get_parameter("SIM_PIN_MASK")
|
off = self.get_parameter("SIM_PIN_MASK")
|
||||||
if on == off:
|
method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=0, p2=1)
|
||||||
raise NotAchievedException(
|
on = self.get_parameter("SIM_PIN_MASK")
|
||||||
"Pin mask unchanged after relay cmd")
|
if on == off:
|
||||||
self.progress("Pin mask changed after relay command")
|
raise NotAchievedException(
|
||||||
self.do_set_relay(0, 0)
|
"Pin mask unchanged after relay cmd")
|
||||||
|
self.progress("Pin mask changed after relay command")
|
||||||
|
method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=0, p2=0)
|
||||||
|
|
||||||
self.set_message_rate_hz("RELAY_STATUS", 10)
|
self.set_message_rate_hz("RELAY_STATUS", 10)
|
||||||
|
|
||||||
# default configuration for relays in sim have one relay:
|
# default configuration for relays in sim have one relay:
|
||||||
self.assert_received_message_field_values('RELAY_STATUS', {
|
self.assert_received_message_field_values('RELAY_STATUS', {
|
||||||
"present": 3,
|
"present": 3,
|
||||||
"on": 0,
|
"on": 0,
|
||||||
})
|
})
|
||||||
self.do_set_relay(0, 1)
|
method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=0, p2=1)
|
||||||
self.assert_received_message_field_values('RELAY_STATUS', {
|
self.assert_received_message_field_values('RELAY_STATUS', {
|
||||||
"present": 3,
|
"present": 3,
|
||||||
"on": 1,
|
"on": 1,
|
||||||
})
|
})
|
||||||
self.do_set_relay(1, 1)
|
method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=1, p2=1)
|
||||||
self.assert_received_message_field_values('RELAY_STATUS', {
|
self.assert_received_message_field_values('RELAY_STATUS', {
|
||||||
"present": 3,
|
"present": 3,
|
||||||
"on": 3,
|
"on": 3,
|
||||||
})
|
})
|
||||||
self.do_set_relay(0, 0)
|
method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=0, p2=0)
|
||||||
self.do_set_relay(1, 0)
|
method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=1, p2=0)
|
||||||
self.assert_received_message_field_values('RELAY_STATUS', {
|
self.assert_received_message_field_values('RELAY_STATUS', {
|
||||||
"present": 3,
|
"present": 3,
|
||||||
"on": 0,
|
"on": 0,
|
||||||
})
|
})
|
||||||
|
|
||||||
# add another servo:
|
# add another servo:
|
||||||
self.set_parameter("RELAY_PIN6", 14)
|
self.set_parameter("RELAY_PIN6", 14)
|
||||||
self.assert_received_message_field_values('RELAY_STATUS', {
|
self.assert_received_message_field_values('RELAY_STATUS', {
|
||||||
"present": 35,
|
"present": 35,
|
||||||
"on": 0,
|
"on": 0,
|
||||||
})
|
})
|
||||||
self.do_set_relay(5, 1)
|
method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=5, p2=1)
|
||||||
self.assert_received_message_field_values('RELAY_STATUS', {
|
self.assert_received_message_field_values('RELAY_STATUS', {
|
||||||
"present": 35,
|
"present": 35,
|
||||||
"on": 32,
|
"on": 32,
|
||||||
})
|
})
|
||||||
self.do_set_relay(0, 1)
|
method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=0, p2=1)
|
||||||
self.assert_received_message_field_values('RELAY_STATUS', {
|
self.assert_received_message_field_values('RELAY_STATUS', {
|
||||||
"present": 35,
|
"present": 35,
|
||||||
"on": 33,
|
"on": 33,
|
||||||
})
|
})
|
||||||
self.do_set_relay(5, 0)
|
method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=5, p2=0)
|
||||||
self.assert_received_message_field_values('RELAY_STATUS', {
|
self.assert_received_message_field_values('RELAY_STATUS', {
|
||||||
"present": 35,
|
"present": 35,
|
||||||
"on": 1,
|
"on": 1,
|
||||||
})
|
})
|
||||||
|
|
||||||
|
self.start_subtest("test MAV_CMD_DO_REPEAT_RELAY")
|
||||||
|
self.context_push()
|
||||||
|
self.set_parameter("SIM_SPEEDUP", 1)
|
||||||
|
method(
|
||||||
|
mavutil.mavlink.MAV_CMD_DO_REPEAT_RELAY,
|
||||||
|
p1=0, # servo 1
|
||||||
|
p2=5, # 5 times
|
||||||
|
p3=0.5, # 1 second between being on
|
||||||
|
)
|
||||||
|
for value in 0, 1, 0, 1, 0, 1, 0, 1:
|
||||||
|
self.wait_message_field_values('RELAY_STATUS', {
|
||||||
|
"on": value,
|
||||||
|
})
|
||||||
|
self.context_pop()
|
||||||
|
self.delay_sim_time(3)
|
||||||
|
self.assert_received_message_field_values('RELAY_STATUS', {
|
||||||
|
"on": 1, # back to initial state
|
||||||
|
})
|
||||||
|
self.context_pop()
|
||||||
|
|
||||||
|
self.start_subtest("test MAV_CMD_DO_SET_SERVO")
|
||||||
|
for value in 1678, 2300, 0:
|
||||||
|
method(mavutil.mavlink.MAV_CMD_DO_SET_SERVO, p1=13, p2=value)
|
||||||
|
self.wait_servo_channel_value(13, value)
|
||||||
|
|
||||||
|
self.start_subtest("test MAV_CMD_DO_REPEAT_SERVO")
|
||||||
|
|
||||||
|
self.context_push()
|
||||||
|
self.set_parameter("SIM_SPEEDUP", 1)
|
||||||
|
trim = self.get_parameter("SERVO13_TRIM")
|
||||||
|
value = 2000
|
||||||
|
method(
|
||||||
|
mavutil.mavlink.MAV_CMD_DO_REPEAT_SERVO,
|
||||||
|
p1=12, # servo12
|
||||||
|
p2=value, # pwm
|
||||||
|
p3=5, # count
|
||||||
|
p4=0.5, # cycle time (1 second between high and high)
|
||||||
|
)
|
||||||
|
for value in trim, value, trim, value, trim, value, trim, value:
|
||||||
|
self.wait_servo_channel_value(12, value)
|
||||||
|
self.context_pop()
|
||||||
|
|
||||||
self.set_message_rate_hz("RELAY_STATUS", 0)
|
self.set_message_rate_hz("RELAY_STATUS", 0)
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user