|
19 | 19 |
|
20 | 20 | Vehicle movement is primarily controlled using the :py:attr:`Vehicle.armed` attribute and
|
21 | 21 | :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 |
24 | 24 | (:py:func:`Vehicle.send_mavlink`, :py:func:`Vehicle.message_factory`).
|
25 | 25 |
|
26 | 26 | 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):
|
68 | 68 |
|
69 | 69 | An object of this type is returned by :py:attr:`Vehicle.attitude`.
|
70 | 70 |
|
| 71 | + .. _figure_attitude: |
| 72 | + |
71 | 73 | .. figure:: http://upload.wikimedia.org/wikipedia/commons/thumb/c/c1/Yaw_Axis_Corrected.svg/500px-Yaw_Axis_Corrected.svg.png
|
72 | 74 | :width: 400px
|
73 | 75 | :alt: Diagram showing Pitch, Roll, Yaw
|
@@ -887,6 +889,9 @@ def listener(self, name, m):
|
887 | 889 | self._mount_yaw = m.pointing_c / 100
|
888 | 890 | self.notify_attribute_listeners('mount', self.mount_status)
|
889 | 891 |
|
| 892 | + # gimbal |
| 893 | + self._gimbal = Gimbal(self) |
| 894 | + |
890 | 895 | # All keys are strings.
|
891 | 896 | self._channels = Channels(self, 8)
|
892 | 897 |
|
@@ -1528,10 +1533,22 @@ def airspeed(self, speed):
|
1528 | 1533 |
|
1529 | 1534 | # send command to vehicle
|
1530 | 1535 | 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 |
1531 | 1546 |
|
1532 | 1547 | @property
|
1533 | 1548 | def mount_status(self):
|
1534 | 1549 | """
|
| 1550 | + .. warning:: This method is deprecated. It has been replaced by :py:attr:`gimbal`. |
| 1551 | + |
1535 | 1552 | Current status of the camera mount (gimbal) as a three element list: ``[ pitch, yaw, roll ]``.
|
1536 | 1553 |
|
1537 | 1554 | The values in the list are set to ``None`` if no mount is configured.
|
@@ -1894,6 +1911,181 @@ def wait_ready(self, *types, **kwargs):
|
1894 | 1911 | return True
|
1895 | 1912 |
|
1896 | 1913 |
|
| 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 | + |
1897 | 2089 | class Parameters(collections.MutableMapping, HasObservers):
|
1898 | 2090 | """
|
1899 | 2091 | This object is used to get and set the values of named parameters for a vehicle. See the following links for information about
|
|
0 commit comments