Skip to content

Commit 373a08b

Browse files
hamishwilleetcr3dr
authored andcommitted
update guided mode instructions for setting speed in positional mode
1 parent f58dedd commit 373a08b

File tree

3 files changed

+54
-78
lines changed

3 files changed

+54
-78
lines changed

docs/examples/guided-set-speed-yaw-demo.rst

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -200,7 +200,6 @@ The functions sending immediate commands are:
200200

201201
* :ref:`condition_yaw() <guided_mode_copter_set_yaw>`
202202
* :ref:`set_roi(location) <guided_mode_copter_set_roi>`
203-
* :ref:`set_speed(speed) <guided_mode_copter_set_speed>`
204203

205204
The example uses a number functions to convert global locations co-ordinates (decimal degrees) into local
206205
coordinates relative to the vehicle (in metres). These are :ref:`described in the guide <guided_mode_copter_useful_conversion_functions>`.

docs/guide/copter/guided_mode.rst

Lines changed: 34 additions & 36 deletions
Original file line numberDiff line numberDiff line change
@@ -58,7 +58,27 @@ to indicate when the vehicle has reached its destination. Developers can use eit
5858
:ref:`measure proximity to the target <example_guided_mode_goto_convenience>` to give the vehicle an
5959
opportunity to reach its destination. The :ref:`example-guided-mode-setting-speed-yaw` shows both approaches.
6060

61-
When moving the vehicle you can send a separate command to :ref:`control the speed <guided_mode_copter_set_speed>` (and other vehicle behaviour).
61+
You can optionally set the target movement speed using the function's ``airspeed`` or ``groundspeed`` parameters
62+
(this is equivalent to setting :py:attr:`Vehicle.airspeed <dronekit.Vehicle.airspeed>`
63+
or :py:attr:`Vehicle.groundspeed <dronekit.Vehicle.groundspeed>`). The speed setting will then be used
64+
for all positional movement commands until it is set to another value.
65+
66+
.. code-block:: python
67+
68+
# Set airspeed using attribute
69+
vehicle.airspeed = 5 #m/s
70+
71+
# Set groundspeed using attribute
72+
vehicle.groundspeed = 7.5 #m/s
73+
74+
# Set groundspeed using `simple_goto()` parameter
75+
vehicle.simple_goto(a_location, groundspeed=10)
76+
77+
.. note::
78+
79+
``Vehicle.simple_goto()`` will use the last speed value set. If both speed values are set at the
80+
same time the resulting behaviour will be vehicle dependent.
81+
6282

6383
.. tip::
6484

@@ -256,13 +276,14 @@ Supported commands
256276
`Copter Commands in Guided Mode <http://dev.ardupilot.com/wiki/copter-commands-in-guided-mode/>`_ lists all the commands that *can* be sent to Copter in GUIDED mode (in fact most of the commands can be sent in any mode!)
257277

258278
DroneKit-Python provides a friendly Python API that abstracts many of the commands.
259-
Where possible you should use the API rather than send messages directly.
260-
For example it is better to use :py:func:`Vehicle.simple_takeoff() <dronekit.Vehicle.simple_takeoff>`
261-
than to explicitly send the ``MAV_CMD_NAV_TAKEOFF`` command.
279+
Where possible you should use the API rather than send messages directly> For example, use:
280+
281+
* :py:func:`Vehicle.simple_takeoff() <dronekit.Vehicle.simple_takeoff>` instead of the ``MAV_CMD_NAV_TAKEOFF`` command.
282+
* :py:func:`Vehicle.simple_goto() <dronekit.Vehicle.simple_goto>`, :py:attr:`Vehicle.airspeed <dronekit.Vehicle.airspeed>`,
283+
or :py:attr:`Vehicle.groundspeed <dronekit.Vehicle.groundspeed>` rather than ``MAV_CMD_DO_CHANGE_SPEED``.
262284

263285
Some of the MAV_CMD commands that you might want to send include:
264286
:ref:`MAV_CMD_CONDITION_YAW <guided_mode_copter_set_yaw>`,
265-
:ref:`MAV_CMD_DO_CHANGE_SPEED <guided_mode_copter_set_speed>`,
266287
:ref:`MAV_CMD_DO_SET_ROI <guided_mode_copter_set_roi>`,
267288
``MAV_CMD_DO_SET_SERVO``,
268289
``MAV_CMD_DO_REPEAT_SERVO``,
@@ -317,36 +338,6 @@ The command allows you to specify that whether the heading is an absolute angle
317338

318339

319340

320-
.. _guided_mode_copter_set_speed:
321-
322-
Setting the speed
323-
-----------------
324-
325-
Send `MAV_CMD_DO_CHANGE_SPEED <http://copter.ardupilot.com/common-mavlink-mission-command-messages-mav_cmd/#mav_cmd_do_change_speed>`_ to change the current speed (metres/second) when travelling to a point.
326-
327-
.. code-block:: python
328-
329-
def set_speed(speed):
330-
msg = vehicle.message_factory.command_long_encode(
331-
0, 0, # target system, target component
332-
mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED, #command
333-
0, #confirmation
334-
0, #param 1
335-
speed, # speed in metres/second
336-
0, 0, 0, 0, 0 #param 3 - 7
337-
)
338-
339-
# send command to vehicle
340-
vehicle.send_mavlink(msg)
341-
342-
343-
The command is useful when setting the vehicle position directly. It is not needed when controlling movement using velocity vectors.
344-
345-
.. note::
346-
347-
In AC3.2.1 Copter will accelerate to the target speed across the journey and then decelerate as it reaches the target. In AC3.3 the speed changes immediately.
348-
349-
350341

351342
.. _guided_mode_copter_set_roi:
352343

@@ -430,7 +421,14 @@ to the Earth's poles.
430421
#New position in decimal degrees
431422
newlat = original_location.lat + (dLat * 180/math.pi)
432423
newlon = original_location.lon + (dLon * 180/math.pi)
433-
return LocationGlobal(newlat, newlon,original_location.alt)
424+
if type(original_location) is LocationGlobal:
425+
targetlocation=LocationGlobal(newlat, newlon,original_location.alt)
426+
elif type(original_location) is LocationGlobalRelative:
427+
targetlocation=LocationGlobalRelative(newlat, newlon,original_location.alt)
428+
else:
429+
raise Exception("Invalid Location object passed")
430+
431+
return targetlocation;
434432
435433
436434
.. code-block:: python

examples/guided_set_speed_yaw/guided_set_speed_yaw.py

Lines changed: 20 additions & 41 deletions
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,4 @@
1+
12
"""
23
guided_set_speed_yaw.py: (Copter Only)
34
@@ -6,7 +7,7 @@
67
Example documentation: http://python.dronekit.io/examples/guided-set-speed-yaw-demo.html
78
"""
89

9-
from dronekit import connect, VehicleMode, LocationGlobal
10+
from dronekit import connect, VehicleMode, LocationGlobal, LocationGlobalRelative
1011
from pymavlink import mavutil # Needed for command message definitions
1112
import time
1213
import math
@@ -132,34 +133,6 @@ def set_roi(location):
132133
vehicle.send_mavlink(msg)
133134

134135

135-
def set_speed(speed):
136-
"""
137-
Send MAV_CMD_DO_CHANGE_SPEED to change the current speed when travelling to a point.
138-
139-
In AC3.2.1 Copter will accelerate to this speed near the centre of its journey and then
140-
decelerate as it reaches the target. In AC3.3 the speed changes immediately.
141-
142-
This method is only useful when controlling the vehicle using position/goto commands.
143-
It is not needed when controlling vehicle movement using velocity components.
144-
145-
For more information see:
146-
http://copter.ardupilot.com/common-mavlink-mission-command-messages-mav_cmd/#mav_cmd_do_change_speed
147-
"""
148-
# create the MAV_CMD_DO_CHANGE_SPEED command
149-
msg = vehicle.message_factory.command_long_encode(
150-
0, 0, # target system, target component
151-
mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED, #command
152-
0, #confirmation
153-
0, #param 1
154-
speed, # speed
155-
0, 0, 0, 0, 0 #param 3 - 7
156-
)
157-
158-
# send command to vehicle
159-
vehicle.send_mavlink(msg)
160-
161-
162-
163136

164137
"""
165138
Functions to make it easy to convert between the different frames-of-reference. In particular these
@@ -197,7 +170,14 @@ def get_location_metres(original_location, dNorth, dEast):
197170
#New position in decimal degrees
198171
newlat = original_location.lat + (dLat * 180/math.pi)
199172
newlon = original_location.lon + (dLon * 180/math.pi)
200-
return LocationGlobal(newlat, newlon,original_location.alt)
173+
if type(original_location) is LocationGlobal:
174+
targetlocation=LocationGlobal(newlat, newlon,original_location.alt)
175+
elif type(original_location) is LocationGlobalRelative:
176+
targetlocation=LocationGlobalRelative(newlat, newlon,original_location.alt)
177+
else:
178+
raise Exception("Invalid Location object passed")
179+
180+
return targetlocation;
201181

202182

203183
def get_distance_metres(aLocation1, aLocation2):
@@ -315,9 +295,6 @@ def goto(dNorth, dEast, gotoFunction=vehicle.simple_goto):
315295
targetLocation=get_location_metres(currentLocation, dNorth, dEast)
316296
targetDistance=get_distance_metres(currentLocation, targetLocation)
317297
gotoFunction(targetLocation)
318-
319-
320-
321298

322299
while vehicle.mode.name=="GUIDED": #Stop action if we are no longer in guided mode.
323300
remainingDistance=get_distance_metres(vehicle.location.global_relative_frame, targetLocation)
@@ -420,8 +397,10 @@ def send_global_velocity(velocity_x, velocity_y, velocity_z, duration):
420397
the distance-to-target.
421398
"""
422399
print("TRIANGLE path using standard Vehicle.simple_goto()")
423-
print("Set speed to 5m/s.")
424-
set_speed(5)
400+
401+
print("Set groundspeed to 5m/s.")
402+
vehicle.groundspeed=5
403+
425404
print("Position North 80 West 50")
426405
goto(80, -50)
427406

@@ -450,17 +429,17 @@ def send_global_velocity(velocity_x, velocity_y, velocity_z, duration):
450429
print("TRIANGLE path using standard SET_POSITION_TARGET_GLOBAL_INT message and with varying speed.")
451430
print("Position South 100 West 130")
452431

453-
print("Set speed to 5m/s.")
454-
set_speed(5)
432+
print("Set groundspeed to 5m/s.")
433+
vehicle.groundspeed=5
455434
goto(-100, -130, goto_position_target_global_int)
456435

457-
print("Set speed to 15m/s (max).")
458-
set_speed(15)
436+
print("Set groundspeed to 15m/s (max).")
437+
vehicle.groundspeed=15
459438
print("Position South 0 East 200")
460439
goto(0, 260, goto_position_target_global_int)
461440

462-
print("Set speed to 10m/s (max).")
463-
set_speed(10)
441+
print("Set airspeed to 10m/s (max).")
442+
vehicle.airspeed=10
464443

465444
print("Position North 100 West 130")
466445
goto(100, -130, goto_position_target_global_int)

0 commit comments

Comments
 (0)