Skip to content

Commit 7963f66

Browse files
committed
mavproxy_mode: add 'guided forward METRES' subcommand
pushes Copter forward or backward without changing the yaw
1 parent d8a2ab5 commit 7963f66

File tree

1 file changed

+64
-1
lines changed

1 file changed

+64
-1
lines changed

Diff for: MAVProxy/modules/mavproxy_mode.py

+64-1
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,10 @@
66
from MAVProxy.modules.lib import mp_module
77
from MAVProxy.modules.lib import mp_util
88

9+
'''
10+
AP_FLAKE8_CLEAN
11+
'''
12+
913

1014
class ModeModule(mp_module.MPModule):
1115
def __init__(self, mpstate):
@@ -67,8 +71,12 @@ def unknown_command(self, args):
6771

6872
def cmd_guided(self, args):
6973
'''set GUIDED target'''
74+
if len(args) > 0:
75+
if args[0] == "forward":
76+
return self.cmd_guided_forward(args[1:])
77+
7078
if len(args) != 1 and len(args) != 3:
71-
print("Usage: guided ALTITUDE | guided LAT LON ALTITUDE")
79+
print("Usage: guided ALTITUDE | guided LAT LON ALTITUDE | guided forward METRES")
7280
return
7381

7482
if len(args) == 3:
@@ -119,6 +127,61 @@ def cmd_guided(self, args):
119127
altitude
120128
)
121129

130+
def build_pt_ignoremask(self, bits, force_not_accel=False):
131+
'''creates an ignore bitmask which ignores all bits except the ones passed in'''
132+
ignore_bits = {
133+
"X": 1, # POSITION_TARGET_TYPEMASK_X_IGNORE
134+
"Y": 2,
135+
"Z": 4,
136+
"VX": 8,
137+
"VY": 16,
138+
"VZ": 32,
139+
"AX": 64,
140+
"AY": 128,
141+
"AZ": 256,
142+
"YAW": 1024,
143+
"YAWRATE": 2048,
144+
}
145+
value = 0
146+
for (n, v) in ignore_bits.items():
147+
if n not in bits:
148+
value |= v
149+
150+
# as of ArduCopter 4.6.0-dev, you can't ignore any axis if you
151+
# want the others to be honoured.
152+
for prefix in "", "V", "A":
153+
for axis in "X", "Y", "Z":
154+
name = f"{prefix}{axis}"
155+
if (value & ignore_bits[name]) == 0:
156+
# not ignoring this axis, so unmark the other axes as ignored
157+
for resetaxis in "X", "Y", "Z":
158+
resetname = f"{prefix}{resetaxis}"
159+
value = value & ~ignore_bits[resetname]
160+
break
161+
162+
if force_not_accel:
163+
value |= 512 # POSITION_TARGET_TYPEMASK_FORCE_SET
164+
165+
return value
166+
167+
def cmd_guided_forward(self, args):
168+
if len(args) != 1:
169+
print("Usage: guided forward METRES")
170+
return
171+
offset = args[0]
172+
# see also "cmd_position" in mavproxy_cmdlong.py
173+
self.master.mav.set_position_target_local_ned_send(
174+
0, # system time in milliseconds
175+
self.settings.target_system, # target system
176+
0, # target component
177+
mavutil.mavlink.MAV_FRAME_BODY_NED,
178+
self.build_pt_ignoremask(["X", "YAWRATE"]), # type mask (pos-x-only)
179+
float(offset), 0, 0, # position x,y,z
180+
0, 0, 0, # velocity x,y,z
181+
0, 0, 0, # accel x,y,z
182+
0, 0 # yaw, yaw rate
183+
)
184+
122185
def mavlink_packet(self, m):
123186
mtype = m.get_type()
124187
if mtype == 'HIGH_LATENCY2':

0 commit comments

Comments
 (0)