Skip to content

Commit 4117856

Browse files
committed
mavproxy_arm: try to use mavlink command to set/unset safety switch
1 parent ea52169 commit 4117856

File tree

1 file changed

+50
-0
lines changed

1 file changed

+50
-0
lines changed

MAVProxy/modules/mavproxy_arm.py

Lines changed: 50 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -58,6 +58,10 @@ def __init__(self, mpstate):
5858
self.add_command('disarm', self.cmd_disarm, 'disarm motors')
5959
self.was_armed = False
6060

61+
# support for setting safety switch position via COMMAND_*
62+
# rather than the "set_mode" message:
63+
self.accepts_DO_SET_SAFETY_SWITCH_STATE = {} # keyed by (sysid, compid)
64+
6165
def checkables(self):
6266
return "<" + "|".join(arming_masks.keys()) + ">"
6367

@@ -156,6 +160,14 @@ def cmd_arm(self, args):
156160
return
157161

158162
if args[0] == "safetyon":
163+
key = (self.target_system, self.target_component)
164+
supports = self.accepts_DO_SET_SAFETY_SWITCH_STATE.get(key, None)
165+
if supports or supports is None:
166+
self.send_DO_SET_SAFETY_SWITCH_STATE(mavutil.mavlink.SAFETY_SWITCH_STATE_SAFE)
167+
168+
if supports is True:
169+
return
170+
159171
self.master.mav.set_mode_send(self.target_system,
160172
mavutil.mavlink.MAV_MODE_FLAG_DECODE_POSITION_SAFETY,
161173
1)
@@ -174,13 +186,36 @@ def cmd_arm(self, args):
174186
return
175187

176188
if args[0] == "safetyoff":
189+
key = (self.target_system, self.target_component)
190+
supports = self.accepts_DO_SET_SAFETY_SWITCH_STATE.get(key, None)
191+
if supports or supports is None:
192+
self.send_DO_SET_SAFETY_SWITCH_STATE(mavutil.mavlink.SAFETY_SWITCH_STATE_DANGEROUS)
193+
194+
if supports is True:
195+
return
196+
177197
self.master.mav.set_mode_send(self.target_system,
178198
mavutil.mavlink.MAV_MODE_FLAG_DECODE_POSITION_SAFETY,
179199
0)
180200
return
181201

182202
print(usage)
183203

204+
def send_DO_SET_SAFETY_SWITCH_STATE(self, state):
205+
self.master.mav.command_long_send(
206+
self.target_system, # target_system
207+
self.target_component,
208+
mavutil.mavlink.MAV_CMD_DO_SET_SAFETY_SWITCH_STATE, # command
209+
0, # confirmation
210+
state, # param1
211+
0, # param2 (all other params meaningless)
212+
0, # param3
213+
0, # param4
214+
0, # param5
215+
0, # param6
216+
0 # param7
217+
)
218+
184219
def cmd_disarm(self, args):
185220
'''disarm motors'''
186221
p2 = 0
@@ -230,7 +265,22 @@ def mavlink_packet(self, m):
230265
v = getattr(rc, 'chan%u_raw' % v)
231266
if v <= 1300:
232267
self.say("ICE Disabled")
268+
return
233269

270+
if mtype == "COMMAND_ACK":
271+
# check to see if the vehicle has bounced our attempts to
272+
# change vehicle state via mavlink command (as opposed to
273+
# old messages which changed state):
274+
accepts_dict = None
275+
if m.command == mavutil.mavlink.MAV_CMD_DO_SET_SAFETY_SWITCH_STATE:
276+
accepts_dict = self.accepts_DO_SET_SAFETY_SWITCH_STATE
277+
if accepts_dict is not None:
278+
key = (m.get_srcSystem(), m.get_srcComponent())
279+
if m.result == mavutil.mavlink.MAV_RESULT_UNSUPPORTED:
280+
# stop sending the commands:
281+
accepts_dict[key] = False
282+
elif m.result in [mavutil.mavlink.MAV_RESULT_ACCEPTED]:
283+
accepts_dict[key] = True
234284

235285
def init(mpstate):
236286
'''initialise module'''

0 commit comments

Comments
 (0)