Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Take set-servo and set-relay commands as COMMAND_INT too #24766

Merged
merged 2 commits into from
Aug 29, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
148 changes: 96 additions & 52 deletions Tools/autotest/rover.py
Original file line number Diff line number Diff line change
Expand Up @@ -582,61 +582,105 @@ def AC_Avoidance(self):

def ServoRelayEvents(self):
'''Test ServoRelayEvents'''
self.do_set_relay(0, 0)
off = self.get_parameter("SIM_PIN_MASK")
self.do_set_relay(0, 1)
on = self.get_parameter("SIM_PIN_MASK")
if on == off:
raise NotAchievedException(
"Pin mask unchanged after relay cmd")
self.progress("Pin mask changed after relay command")
self.do_set_relay(0, 0)
for method in self.run_cmd, self.run_cmd_int:
self.context_push()
method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=0, p2=0)
off = self.get_parameter("SIM_PIN_MASK")
method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=0, p2=1)
on = self.get_parameter("SIM_PIN_MASK")
if on == off:
raise NotAchievedException(
"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:
self.assert_received_message_field_values('RELAY_STATUS', {
"present": 3,
"on": 0,
})
self.do_set_relay(0, 1)
self.assert_received_message_field_values('RELAY_STATUS', {
"present": 3,
"on": 1,
})
self.do_set_relay(1, 1)
self.assert_received_message_field_values('RELAY_STATUS', {
"present": 3,
"on": 3,
})
self.do_set_relay(0, 0)
self.do_set_relay(1, 0)
self.assert_received_message_field_values('RELAY_STATUS', {
"present": 3,
"on": 0,
})
# default configuration for relays in sim have one relay:
self.assert_received_message_field_values('RELAY_STATUS', {
"present": 3,
"on": 0,
})
method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=0, p2=1)
self.assert_received_message_field_values('RELAY_STATUS', {
"present": 3,
"on": 1,
})
method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=1, p2=1)
self.assert_received_message_field_values('RELAY_STATUS', {
"present": 3,
"on": 3,
})
method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=0, p2=0)
method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=1, p2=0)
self.assert_received_message_field_values('RELAY_STATUS', {
"present": 3,
"on": 0,
})

# add another servo:
self.set_parameter("RELAY_PIN6", 14)
self.assert_received_message_field_values('RELAY_STATUS', {
"present": 35,
"on": 0,
})
self.do_set_relay(5, 1)
self.assert_received_message_field_values('RELAY_STATUS', {
"present": 35,
"on": 32,
})
self.do_set_relay(0, 1)
self.assert_received_message_field_values('RELAY_STATUS', {
"present": 35,
"on": 33,
})
self.do_set_relay(5, 0)
self.assert_received_message_field_values('RELAY_STATUS', {
"present": 35,
"on": 1,
})
# add another servo:
self.set_parameter("RELAY_PIN6", 14)
self.assert_received_message_field_values('RELAY_STATUS', {
"present": 35,
"on": 0,
})
method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=5, p2=1)
self.assert_received_message_field_values('RELAY_STATUS', {
"present": 35,
"on": 32,
})
method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=0, p2=1)
self.assert_received_message_field_values('RELAY_STATUS', {
"present": 35,
"on": 33,
})
method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=5, p2=0)
self.assert_received_message_field_values('RELAY_STATUS', {
"present": 35,
"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)

Expand Down
2 changes: 1 addition & 1 deletion libraries/GCS_MAVLink/GCS.h
Original file line number Diff line number Diff line change
Expand Up @@ -769,7 +769,7 @@ class GCS_MAVLINK

virtual void handleMessage(const mavlink_message_t &msg) = 0;

MAV_RESULT handle_servorelay_message(const mavlink_command_long_t &packet);
MAV_RESULT handle_servorelay_message(const mavlink_command_int_t &packet);
bool send_relay_status() const;

static bool command_long_stores_location(const MAV_CMD command);
Expand Down
17 changes: 8 additions & 9 deletions libraries/GCS_MAVLink/GCS_Common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4839,15 +4839,6 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t
result = handle_command_request_message(packet);
break;

#if AP_SERVORELAYEVENTS_ENABLED
case MAV_CMD_DO_SET_SERVO:
case MAV_CMD_DO_REPEAT_SERVO:
case MAV_CMD_DO_SET_RELAY:
case MAV_CMD_DO_REPEAT_RELAY:
result = handle_servorelay_message(packet);
break;
#endif

case MAV_CMD_DO_FLIGHTTERMINATION:
result = handle_flight_termination(packet);
break;
Expand Down Expand Up @@ -5174,6 +5165,14 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &p
return handle_command_mag_cal(packet);
#endif

#if AP_SERVORELAYEVENTS_ENABLED
case MAV_CMD_DO_SET_SERVO:
case MAV_CMD_DO_REPEAT_SERVO:
case MAV_CMD_DO_SET_RELAY:
case MAV_CMD_DO_REPEAT_RELAY:
return handle_servorelay_message(packet);
#endif

#if AP_SCRIPTING_ENABLED
case MAV_CMD_SCRIPTING:
{
Expand Down
4 changes: 2 additions & 2 deletions libraries/GCS_MAVLink/GCS_ServoRelay.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@

#if AP_SERVORELAYEVENTS_ENABLED

MAV_RESULT GCS_MAVLINK::handle_servorelay_message(const mavlink_command_long_t &packet)
MAV_RESULT GCS_MAVLINK::handle_servorelay_message(const mavlink_command_int_t &packet)
{
AP_ServoRelayEvents *handler = AP::servorelayevents();
if (handler == nullptr) {
Expand Down Expand Up @@ -48,4 +48,4 @@ MAV_RESULT GCS_MAVLINK::handle_servorelay_message(const mavlink_command_long_t &
return result;
}

#endif
#endif // AP_SERVORELAYEVENTS_ENABLED