Skip to content
This repository was archived by the owner on Feb 6, 2024. It is now read-only.

Commit ad1cb4d

Browse files
committed
Merge pull request dronekit#498 from dronekit/djnugent-gimbal-control
Gimbal: Added gimbal control
2 parents 33584e9 + 0121fb6 commit ad1cb4d

File tree

4 files changed

+230
-25
lines changed

4 files changed

+230
-25
lines changed

docs/examples/vehicle_state.rst

Lines changed: 7 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -18,10 +18,12 @@ The example can be run as described in :doc:`running_examples` (which in turn as
1818
the vehicle and DroneKit have been set up as described in :ref:`get-started`).
1919

2020
If you're using a simulated vehicle remember to :ref:`disable arming checks <disable-arming-checks>` so
21-
that the example can run. You can also
22-
`add a virtual rangefinder <http://dev.ardupilot.com/wiki/using-sitl-for-ardupilot-testing/#adding_a_virtual_rangefinder>`_
23-
(otherwise the :py:attr:`Vehicle.rangefinder <dronekit.Vehicle.rangefinder>` attribute may return
24-
values of ``None`` for the distance and voltage).
21+
that the example can run. You can also:
22+
23+
* `add a virtual rangefinder <http://dev.ardupilot.com/wiki/using-sitl-for-ardupilot-testing/#adding_a_virtual_rangefinder>`_
24+
(otherwise the :py:attr:`Vehicle.rangefinder <dronekit.Vehicle.rangefinder>` attribute may return values of ``None`` for the distance and voltage).
25+
* `add a virtual gimbal <http://dev.ardupilot.com/wiki/using-sitl-for-ardupilot-testing/#adding_a_virtual_gimbal>`_
26+
(otherwise the :py:attr:`Vehicle.gimbal <dronekit.Vehicle.gimbal>` attribute may return values of ``None`` for the yaw, pitch and roll).
2527

2628
In summary, after cloning the repository:
2729

@@ -64,7 +66,7 @@ On the command prompt you should see (something like):
6466
Attitude: Attitude:pitch=0.00294387154281,yaw=-0.11805768311,roll=0.00139428151306
6567
Velocity: [-0.03, 0.02, 0.0]
6668
GPS: GPSInfo:fix=3,num_sat=10
67-
Mount status: [None, None, None]
69+
Gimbal status: Gimbal: pitch=None, roll=None, yaw=None
6870
Battery: Battery:voltage=12.587,current=0.0,level=100
6971
EKF OK?: False
7072
Last Heartbeat: 0.769999980927

docs/guide/vehicle_state_and_parameters.rst

Lines changed: 28 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,7 @@ Vehicle state information is exposed through vehicle *attributes*. DroneKit-Pyth
2727
:py:attr:`Vehicle.attitude <dronekit.Vehicle.attitude>`,
2828
:py:attr:`Vehicle.velocity <dronekit.Vehicle.velocity>`,
2929
:py:attr:`Vehicle.gps_0 <dronekit.Vehicle.gps_0>`,
30-
:py:attr:`Vehicle.mount_status <dronekit.Vehicle.mount_status>`,
30+
:py:attr:`Vehicle.gimbal <dronekit.Vehicle.gimbal>`,
3131
:py:attr:`Vehicle.battery <dronekit.Vehicle.battery>`,
3232
:py:attr:`Vehicle.rangefinder <dronekit.Vehicle.rangefinder>`,
3333
:py:attr:`Vehicle.ekf_ok <dronekit.Vehicle.ekf_ok>`,
@@ -46,11 +46,12 @@ Attributes are initially created with ``None`` values for their members. In most
4646

4747
All of the attributes can be :ref:`read <vehicle_state_read_attributes>`,
4848
but only the :py:attr:`Vehicle.home_location <dronekit.Vehicle.home_location>`,
49+
:py:attr:`Vehicle.gimbal <dronekit.Vehicle.gimbal>`
4950
:py:attr:`Vehicle.airspeed <dronekit.Vehicle.airspeed>`,
5051
:py:attr:`Vehicle.groundspeed <dronekit.Vehicle.groundspeed>`,
5152
:py:attr:`Vehicle.mode <dronekit.Vehicle.mode>` and
5253
:py:attr:`Vehicle.armed <dronekit.Vehicle.armed>`
53-
status can be :ref:`written <vehicle_state_set_attributes>`.
54+
status can be :ref:`set <vehicle_state_set_attributes>`.
5455

5556
Almost all of the attributes can be :ref:`observed <vehicle_state_observe_attributes>`.
5657

@@ -76,7 +77,7 @@ regularly updated from MAVLink messages sent by the vehicle).
7677
print "GPS: %s" % vehicle.gps_0
7778
print "Groundspeed: %s" % vehicle.groundspeed
7879
print "Airspeed: %s" % vehicle.airspeed
79-
print "Mount status: %s" % vehicle.mount_status
80+
print "Gimbal status: %s" % vehicle.gimbal
8081
print "Battery: %s" % vehicle.battery
8182
print "EKF OK?: %s" % vehicle.ekf_ok
8283
print "Last Heartbeat: %s" % vehicle.last_heartbeat
@@ -114,11 +115,12 @@ regularly updated from MAVLink messages sent by the vehicle).
114115
Setting attributes
115116
------------------
116117

117-
Only the :py:attr:`Vehicle.mode <dronekit.Vehicle.mode>` :py:attr:`Vehicle.armed <dronekit.Vehicle.armed>`
118+
The :py:attr:`Vehicle.mode <dronekit.Vehicle.mode>`, :py:attr:`Vehicle.armed <dronekit.Vehicle.armed>`
118119
, :py:attr:`Vehicle.airspeed <dronekit.Vehicle.airspeed>` and :py:attr:`Vehicle.groundspeed <dronekit.Vehicle.groundspeed>`,
119-
attributes can be written (``Vehicle.home_location`` is a special case, as :ref:`discussed below <vehicle_state_home_location>`).
120+
attributes can all be "directly" written (:py:attr:`Vehicle.home_location <dronekit.Vehicle.home_location>` can also be directly written,
121+
but has special considerations that are :ref:`discussed below <vehicle_state_home_location>`).
120122

121-
The attributes are set by assigning a value:
123+
These attributes are set by assigning a value:
122124

123125
.. code:: python
124126
@@ -128,18 +130,9 @@ The attributes are set by assigning a value:
128130
#set the default groundspeed to be used in movement commands
129131
vehicle.groundspeed = 3.2
130132
131-
.. warning::
132133
133-
Changing a value is **not guaranteed to succeed**.
134-
For example, vehicle arming can fail if the vehicle doesn't pass pre-arming checks,
135-
and it is possible that the message will not even arrive at the vehicle.
136-
137-
While the autopilot does send information about the success (or failure) of the request,
138-
this is `not currently handled by DroneKit <https://github.com/dronekit/dronekit-python/issues/114>`_.
139-
140-
141-
Code should not assume that an attempt to set an attribute will succeed. The example code snippet below polls the attribute values
142-
to confirm they have changed before proceeding.
134+
Commands to change a value are **not guaranteed to succeed** (or even to be received) and code should be written with this in mind.
135+
For example, the code snippet below polls the attribute values to confirm they have changed before proceeding.
143136

144137
.. code:: python
145138
@@ -149,6 +142,24 @@ to confirm they have changed before proceeding.
149142
print " Getting ready to take off ..."
150143
time.sleep(1)
151144
145+
.. note::
146+
147+
While the autopilot does send information about the success (or failure) of the request,
148+
this is `not currently handled by DroneKit <https://github.com/dronekit/dronekit-python/issues/114>`_.
149+
150+
:py:attr:`Vehicle.gimbal <dronekit.Vehicle.gimbal>` can't be written directly, but the gimbal can be controlled using the
151+
:py:func:`Vehicle.gimbal.rotate() <dronekit.Gimbal.rotate>` and :py:func:`Vehicle.gimbal.target_location() <dronekit.Gimbal.target_location>`
152+
methods. The first method lets you set the precise orientation of the gimbal while the second makes the gimbal track a specific "region of interest".
153+
154+
.. code:: python
155+
156+
#Point the gimbal straight down
157+
vehicle.gimbal.rotate(-90, 0, 0)
158+
time.sleep(10)
159+
160+
#Set the camera to track the current home position.
161+
vehicle.gimbal.target_location(vehicle.home_location)
162+
time.sleep(10)
152163
153164
154165
.. _vehicle_state_observe_attributes:

dronekit/__init__.py

Lines changed: 194 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -19,8 +19,8 @@
1919
2020
Vehicle movement is primarily controlled using the :py:attr:`Vehicle.armed` attribute and
2121
:py:func:`Vehicle.simple_takeoff` and :py:attr:`Vehicle.simple_goto` in GUIDED mode.
22-
Control over speed, direction, altitude, camera trigger and any other aspect of the vehicle is supported
23-
using custom MAVLink messages
22+
23+
Velocity-based movement and control over other vehicle features can be achieved using custom MAVLink messages
2424
(:py:func:`Vehicle.send_mavlink`, :py:func:`Vehicle.message_factory`).
2525
2626
It is also possible to work with vehicle "missions" using the :py:attr:`Vehicle.commands` attribute, and run them in AUTO mode.
@@ -68,6 +68,8 @@ class Attitude(object):
6868
6969
An object of this type is returned by :py:attr:`Vehicle.attitude`.
7070
71+
.. _figure_attitude:
72+
7173
.. figure:: http://upload.wikimedia.org/wikipedia/commons/thumb/c/c1/Yaw_Axis_Corrected.svg/500px-Yaw_Axis_Corrected.svg.png
7274
:width: 400px
7375
:alt: Diagram showing Pitch, Roll, Yaw
@@ -887,6 +889,9 @@ def listener(self, name, m):
887889
self._mount_yaw = m.pointing_c / 100
888890
self.notify_attribute_listeners('mount', self.mount_status)
889891

892+
# gimbal
893+
self._gimbal = Gimbal(self)
894+
890895
# All keys are strings.
891896
self._channels = Channels(self, 8)
892897

@@ -1528,10 +1533,22 @@ def airspeed(self, speed):
15281533

15291534
# send command to vehicle
15301535
self.send_mavlink(msg)
1536+
1537+
1538+
@property
1539+
def gimbal(self):
1540+
"""
1541+
Gimbal object for controlling, viewing and observing gimbal status (:py:class:`Gimbal`).
1542+
1543+
.. versionadded:: 2.1.0
1544+
"""
1545+
return self._gimbal
15311546

15321547
@property
15331548
def mount_status(self):
15341549
"""
1550+
.. warning:: This method is deprecated. It has been replaced by :py:attr:`gimbal`.
1551+
15351552
Current status of the camera mount (gimbal) as a three element list: ``[ pitch, yaw, roll ]``.
15361553
15371554
The values in the list are set to ``None`` if no mount is configured.
@@ -1894,6 +1911,181 @@ def wait_ready(self, *types, **kwargs):
18941911
return True
18951912

18961913

1914+
class Gimbal(object):
1915+
"""
1916+
Gimbal status and control.
1917+
1918+
An object of this type is returned by :py:attr:`Vehicle.gimbal`. The
1919+
gimbal orientation can be obtained from its :py:attr:`roll`, :py:attr:`pitch` and
1920+
:py:attr:`yaw` attributes.
1921+
1922+
The gimbal orientation can be set explicitly using :py:func:`rotate`
1923+
or you can set the gimbal (and vehicle) to track a specific "region of interest" using
1924+
:py:func:`target_location`.
1925+
1926+
.. note::
1927+
1928+
* The orientation attributes are created with values of ``None``. If a gimbal is present,
1929+
the attributes are populated shortly after initialisation by messages from the autopilot.
1930+
* The attribute values reflect the last gimbal setting-values rather than actual measured values.
1931+
This means that the values won't change if you manually move the gimbal, and that the value
1932+
will change when you set it, even if the specified orientation is not supported.
1933+
* A gimbal may not support all axes of rotation. For example, the Solo gimbal will set pitch
1934+
values from 0 to -90 (straight ahead to straight down), it will rotate the vehicle to follow specified
1935+
yaw values, and will ignore roll commands (not supported).
1936+
"""
1937+
1938+
def __init__(self, vehicle):
1939+
super(Gimbal, self).__init__()
1940+
1941+
self._pitch = None
1942+
self._roll = None
1943+
self._yaw = None
1944+
self._vehicle = vehicle
1945+
1946+
@vehicle.on_message('MOUNT_STATUS')
1947+
def listener(vehicle, name, m):
1948+
self._pitch = m.pointing_a / 100
1949+
self._roll = m.pointing_b / 100
1950+
self._yaw = m.pointing_c / 100
1951+
vehicle.notify_attribute_listeners('gimbal', vehicle.gimbal)
1952+
1953+
@property
1954+
def pitch(self):
1955+
"""
1956+
Gimbal pitch in degrees relative to the vehicle (see diagram for :ref:`attitude <figure_attitude>`).
1957+
A value of 0 represents a camera pointed straight ahead relative to the front of the vehicle,
1958+
while -90 points the camera straight down.
1959+
1960+
.. note::
1961+
1962+
This is the last pitch value sent to the gimbal (not the actual/measured pitch).
1963+
"""
1964+
return self._pitch
1965+
1966+
@property
1967+
def roll(self):
1968+
"""
1969+
Gimbal roll in degrees relative to the vehicle (see diagram for :ref:`attitude <figure_attitude>`).
1970+
1971+
.. note::
1972+
1973+
This is the last roll value sent to the gimbal (not the actual/measured roll).
1974+
"""
1975+
return self._roll
1976+
1977+
@property
1978+
def yaw(self):
1979+
"""
1980+
Gimbal yaw in degrees relative to *global frame* (0 is North, 90 is West, 180 is South etc).
1981+
1982+
.. note::
1983+
1984+
This is the last yaw value sent to the gimbal (not the actual/measured yaw).
1985+
"""
1986+
return self._yaw
1987+
1988+
def rotate(self, pitch, roll, yaw):
1989+
"""
1990+
Rotate the gimbal to a specific vector.
1991+
1992+
.. code-block:: python
1993+
1994+
#Point the gimbal straight down
1995+
vehicle.gimbal.rotate(-90, 0, 0)
1996+
1997+
:param pitch: Gimbal pitch in degrees relative to the vehicle (see diagram for :ref:`attitude <figure_attitude>`).
1998+
A value of 0 represents a camera pointed straight ahead relative to the front of the vehicle,
1999+
while -90 points the camera straight down.
2000+
:param roll: Gimbal roll in degrees relative to the vehicle (see diagram for :ref:`attitude <figure_attitude>`).
2001+
:param yaw: Gimbal yaw in degrees relative to *global frame* (0 is North, 90 is West, 180 is South etc.)
2002+
"""
2003+
msg = self._vehicle.message_factory.mount_configure_encode(
2004+
0, 1, # target system, target component
2005+
mavutil.mavlink.MAV_MOUNT_MODE_MAVLINK_TARGETING, #mount_mode
2006+
1, # stabilize roll
2007+
1, # stabilize pitch
2008+
1, # stabilize yaw
2009+
)
2010+
self._vehicle.send_mavlink(msg)
2011+
msg = self._vehicle.message_factory.mount_control_encode(
2012+
0, 1, # target system, target component
2013+
pitch * 100, # pitch is in centidegrees
2014+
roll * 100, # roll
2015+
yaw * 100, # yaw is in centidegrees
2016+
0) # save position
2017+
self._vehicle.send_mavlink(msg)
2018+
2019+
def target_location(self,roi):
2020+
"""
2021+
Point the gimbal at a specific region of interest (ROI).
2022+
2023+
.. code-block:: python
2024+
2025+
#Set the camera to track the current home location.
2026+
vehicle.gimbal.target_location(vehicle.home_location)
2027+
2028+
The target position must be defined in a :py:class:`LocationGlobalRelative` or :py:class:`LocationGlobal`.
2029+
2030+
This function can be called in AUTO or GUIDED mode.
2031+
2032+
In order to clear an ROI you can send a location with all zeros (e.g. ``LocationGlobalRelative(0,0,0)``).
2033+
2034+
:param roi: Target location in global relative frame.
2035+
"""
2036+
#set gimbal to targeting mode
2037+
msg = self._vehicle.message_factory.mount_configure_encode(
2038+
0, 1, # target system, target component
2039+
mavutil.mavlink.MAV_MOUNT_MODE_GPS_POINT, #mount_mode
2040+
1, # stabilize roll
2041+
1, # stabilize pitch
2042+
1, # stabilize yaw
2043+
)
2044+
self._vehicle.send_mavlink(msg)
2045+
2046+
#Get altitude relative to home irrespective of Location object passed in.
2047+
if isinstance(roi, LocationGlobalRelative):
2048+
alt = roi.alt
2049+
elif isinstance(roi, LocationGlobal):
2050+
if not self.home_location:
2051+
self.commands.download()
2052+
self.commands.wait_ready()
2053+
alt = roi.alt - self.home_location.alt
2054+
else:
2055+
raise APIException('Expecting location to be LocationGlobal or LocationGlobalRelative.')
2056+
2057+
#set the ROI
2058+
msg = self._vehicle.message_factory.command_long_encode(
2059+
0, 1, # target system, target component
2060+
mavutil.mavlink.MAV_CMD_DO_SET_ROI, #command
2061+
0, #confirmation
2062+
0, 0, 0, 0, #params 1-4
2063+
roi.lat,
2064+
roi.lon,
2065+
alt
2066+
)
2067+
self._vehicle.send_mavlink(msg)
2068+
2069+
def release(self):
2070+
"""
2071+
Release control of the gimbal to the user (RC Control).
2072+
2073+
This should be called once you've finished controlling the mount with either :py:func:`rotate`
2074+
or :py:func:`target_location`. Control will automatically be released if you change vehicle mode.
2075+
"""
2076+
msg = self._vehicle.message_factory.mount_configure_encode(
2077+
0, 1, # target system, target component
2078+
mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING, #mount_mode
2079+
1, # stabilize roll
2080+
1, # stabilize pitch
2081+
1, # stabilize yaw
2082+
)
2083+
self._vehicle.send_mavlink(msg)
2084+
2085+
def __str__(self):
2086+
return "Gimbal: pitch={0}, roll={1}, yaw={2}".format(self.pitch, self.roll, self.yaw)
2087+
2088+
18972089
class Parameters(collections.MutableMapping, HasObservers):
18982090
"""
18992091
This object is used to get and set the values of named parameters for a vehicle. See the following links for information about

examples/vehicle_state/vehicle_state.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -31,7 +31,7 @@
3131
print " Attitude: %s" % vehicle.attitude
3232
print " Velocity: %s" % vehicle.velocity
3333
print " GPS: %s" % vehicle.gps_0
34-
print " Mount status: %s" % vehicle.mount_status
34+
print " Gimbal status: %s" % vehicle.gimbal
3535
print " Battery: %s" % vehicle.battery
3636
print " EKF OK?: %s" % vehicle.ekf_ok
3737
print " Last Heartbeat: %s" % vehicle.last_heartbeat

0 commit comments

Comments
 (0)