Skip to content

Commit

Permalink
mavproxy_mode: use MAV_CMD_DO_REPOSITION for 'Fly To'
Browse files Browse the repository at this point in the history
this has the advantage that you don't need to be in guided mode to start the command.  Prevents some clunky interactions between pilot and GCS operator as the vehicle does not need to be somewhere safe to loiter before the command can be safely issued.
  • Loading branch information
peterbarker authored and tridge committed Aug 11, 2023
1 parent d039c8a commit 67839c7
Show file tree
Hide file tree
Showing 2 changed files with 20 additions and 0 deletions.
1 change: 1 addition & 0 deletions MAVProxy/mavproxy.py
Original file line number Diff line number Diff line change
Expand Up @@ -267,6 +267,7 @@ def __init__(self):
MPSetting('rallyalt', int, 90, 'Default Rally Altitude', range=(0,10000), increment=1),
MPSetting('terrainalt', str, 'Auto', 'Use terrain altitudes', choice=['Auto','True','False']),
MPSetting('guidedalt', int, 100, 'Default "Fly To" Altitude', range=(0,10000), increment=1),
MPSetting('guided_use_reposition', bool, True, 'Use MAV_CMD_DO_REPOSITION for guided fly-to'),
MPSetting('rally_breakalt', int, 40, 'Default Rally Break Altitude', range=(0,10000), increment=1),
MPSetting('rally_flags', int, 0, 'Default Rally Flags', range=(0,10000), increment=1),

Expand Down
19 changes: 19 additions & 0 deletions MAVProxy/modules/mavproxy_mode.py
Original file line number Diff line number Diff line change
Expand Up @@ -84,6 +84,25 @@ def cmd_guided(self, args):
altitude = float(args[0])

print("Guided %s %s" % (str(latlon), str(altitude)))

if self.settings.guided_use_reposition:
self.master.mav.command_int_send(
self.settings.target_system,
self.settings.target_component,
self.module('wp').get_default_frame(),
mavutil.mavlink.MAV_CMD_DO_REPOSITION,
0, # current
0, # autocontinue
-1, # p1 - ground speed, -1 is use-default
mavutil.mavlink.MAV_DO_REPOSITION_FLAGS_CHANGE_MODE, # p2 - flags
0, # p3 - loiter radius for Planes, 0 is ignored
0, # p4 - yaw - 0 is loiter clockwise
int(latlon[0]*1.0e7),
int(latlon[1]*1.0e7),
altitude
)
return

self.master.mav.mission_item_int_send(
self.settings.target_system,
self.settings.target_component,
Expand Down

0 comments on commit 67839c7

Please sign in to comment.