forked from dronekit/dronekit-python
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy path__init__.py
3221 lines (2450 loc) · 124 KB
/
__init__.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
# DroneAPI module
"""
This is the API Reference for the DroneKit-Python API.
The main API is the :py:class:`Vehicle` class.
The code snippet below shows how to use :py:func:`connect` to obtain an instance of a connected vehicle:
.. code:: python
from dronekit import connect
# Connect to the Vehicle using "connection string" (in this case an address on network)
vehicle = connect('127.0.0.1:14550', wait_ready=True)
:py:class:`Vehicle` provides access to vehicle *state* through python attributes
(e.g. :py:attr:`Vehicle.mode`)
and to settings/parameters though the :py:attr:`Vehicle.parameters` attribute.
Asynchronous notification on vehicle attribute changes is available by registering listeners/observers.
Vehicle movement is primarily controlled using the :py:attr:`Vehicle.armed` attribute and
:py:func:`Vehicle.simple_takeoff` and :py:attr:`Vehicle.simple_goto` in GUIDED mode.
Velocity-based movement and control over other vehicle features can be achieved using custom MAVLink messages
(:py:func:`Vehicle.send_mavlink`, :py:func:`Vehicle.message_factory`).
It is also possible to work with vehicle "missions" using the :py:attr:`Vehicle.commands` attribute, and run them in AUTO mode.
All the logging is handled through the builtin Python `logging` module.
A number of other useful classes and methods are listed below.
----
"""
import sys
import collections
# Python3.10 removed MutableMapping from collections:
if sys.version_info.major == 3 and sys.version_info.minor >= 10:
from collections.abc import MutableMapping
else:
from collections import MutableMapping
import copy
import logging
import math
import struct
import time
import monotonic
from past.builtins import basestring
from pymavlink import mavutil, mavwp
from pymavlink.dialects.v10 import ardupilotmega
from dronekit.util import ErrprinterHandler
class APIException(Exception):
"""
Base class for DroneKit related exceptions.
:param String message: Message string describing the exception
"""
class TimeoutError(APIException):
'''Raised by operations that have timeouts.'''
class Attitude(object):
"""
Attitude information.
An object of this type is returned by :py:attr:`Vehicle.attitude`.
.. _figure_attitude:
.. figure:: http://upload.wikimedia.org/wikipedia/commons/thumb/c/c1/Yaw_Axis_Corrected.svg/500px-Yaw_Axis_Corrected.svg.png
:width: 400px
:alt: Diagram showing Pitch, Roll, Yaw
:target: http://commons.wikimedia.org/wiki/File:Yaw_Axis_Corrected.svg
Diagram showing Pitch, Roll, Yaw (`Creative Commons <http://commons.wikimedia.org/wiki/File:Yaw_Axis_Corrected.svg>`_)
:param pitch: Pitch in radians
:param yaw: Yaw in radians
:param roll: Roll in radians
"""
def __init__(self, pitch, yaw, roll):
self.pitch = pitch
self.yaw = yaw
self.roll = roll
def __str__(self):
fmt = '{}:pitch={pitch},yaw={yaw},roll={roll}'
return fmt.format(self.__class__.__name__, **vars(self))
class LocationGlobal(object):
"""
A global location object.
The latitude and longitude are relative to the `WGS84 coordinate system <http://en.wikipedia.org/wiki/World_Geodetic_System>`_.
The altitude is relative to mean sea-level (MSL).
For example, a global location object with altitude 30 metres above sea level might be defined as:
.. code:: python
LocationGlobal(-34.364114, 149.166022, 30)
.. todo:: FIXME: Location class - possibly add a vector3 representation.
An object of this type is owned by :py:attr:`Vehicle.location`. See that class for information on
reading and observing location in the global frame.
:param lat: Latitude.
:param lon: Longitude.
:param alt: Altitude in meters relative to mean sea-level (MSL).
"""
def __init__(self, lat, lon, alt=None):
self.lat = lat
self.lon = lon
self.alt = alt
# This is for backward compatibility.
self.local_frame = None
self.global_frame = None
def __str__(self):
return "LocationGlobal:lat=%s,lon=%s,alt=%s" % (self.lat, self.lon, self.alt)
class LocationGlobalRelative(object):
"""
A global location object, with attitude relative to home location altitude.
The latitude and longitude are relative to the `WGS84 coordinate system <http://en.wikipedia.org/wiki/World_Geodetic_System>`_.
The altitude is relative to the *home position*.
For example, a ``LocationGlobalRelative`` object with an altitude of 30 metres above the home location might be defined as:
.. code:: python
LocationGlobalRelative(-34.364114, 149.166022, 30)
.. todo:: FIXME: Location class - possibly add a vector3 representation.
An object of this type is owned by :py:attr:`Vehicle.location`. See that class for information on
reading and observing location in the global-relative frame.
:param lat: Latitude.
:param lon: Longitude.
:param alt: Altitude in meters (relative to the home location).
"""
def __init__(self, lat, lon, alt=None):
self.lat = lat
self.lon = lon
self.alt = alt
# This is for backward compatibility.
self.local_frame = None
self.global_frame = None
def __str__(self):
return "LocationGlobalRelative:lat=%s,lon=%s,alt=%s" % (self.lat, self.lon, self.alt)
class LocationLocal(object):
"""
A local location object.
The north, east and down are relative to the EKF origin. This is most likely the location where the vehicle was turned on.
An object of this type is owned by :py:attr:`Vehicle.location`. See that class for information on
reading and observing location in the local frame.
:param north: Position north of the EKF origin in meters.
:param east: Position east of the EKF origin in meters.
:param down: Position down from the EKF origin in meters. (i.e. negative altitude in meters)
"""
def __init__(self, north, east, down):
self.north = north
self.east = east
self.down = down
def __str__(self):
return "LocationLocal:north=%s,east=%s,down=%s" % (self.north, self.east, self.down)
def distance_home(self):
"""
Distance away from home, in meters. Returns 3D distance if `down` is known, otherwise 2D distance.
"""
if self.north is not None and self.east is not None:
if self.down is not None:
return math.sqrt(self.north**2 + self.east**2 + self.down**2)
else:
return math.sqrt(self.north**2 + self.east**2)
class GPSInfo(object):
"""
Standard information about GPS.
If there is no GPS lock the parameters are set to ``None``.
:param Int eph: GPS horizontal dilution of position (HDOP).
:param Int epv: GPS vertical dilution of position (VDOP).
:param Int fix_type: 0-1: no fix, 2: 2D fix, 3: 3D fix
:param Int satellites_visible: Number of satellites visible.
.. todo:: FIXME: GPSInfo class - possibly normalize eph/epv? report fix type as string?
"""
def __init__(self, eph, epv, fix_type, satellites_visible):
self.eph = eph
self.epv = epv
self.fix_type = fix_type
self.satellites_visible = satellites_visible
def __str__(self):
return "GPSInfo:fix=%s,num_sat=%s" % (self.fix_type, self.satellites_visible)
class Wind(object):
"""
Wind information
An object of this type is returned by :py:attr: `Vehicle.wind`.
:param wind_direction: Wind direction in degrees
:param wind_speed: Wind speed in m/s
:param wind_speed_z: vertical wind speed in m/s
"""
def __init__(self, wind_direction, wind_speed, wind_speed_z):
self.wind_direction = wind_direction
self.wind_speed = wind_speed
self.wind_speed_z = wind_speed_z
def __str__(self):
return "Wind: wind direction: {}, wind speed: {}, wind speed z: {}".format(self.wind_direction, self.wind_speed, self.wind_speed_z)
class Battery(object):
"""
System battery information.
An object of this type is returned by :py:attr:`Vehicle.battery`.
:param voltage: Battery voltage in millivolts.
:param current: Battery current, in 10 * milliamperes. ``None`` if the autopilot does not support current measurement.
:param level: Remaining battery energy. ``None`` if the autopilot cannot estimate the remaining battery.
"""
def __init__(self, voltage, current, level):
self.voltage = voltage / 1000.0
if current == -1:
self.current = None
else:
self.current = current / 100.0
if level == -1:
self.level = None
else:
self.level = level
def __str__(self):
return "Battery:voltage={},current={},level={}".format(self.voltage, self.current,
self.level)
class Rangefinder(object):
"""
Rangefinder readings.
An object of this type is returned by :py:attr:`Vehicle.rangefinder`.
:param distance: Distance (metres). ``None`` if the vehicle doesn't have a rangefinder.
:param voltage: Voltage (volts). ``None`` if the vehicle doesn't have a rangefinder.
"""
def __init__(self, distance, voltage):
self.distance = distance
self.voltage = voltage
def __str__(self):
return "Rangefinder: distance={}, voltage={}".format(self.distance, self.voltage)
class Version(object):
"""
Autopilot version and type.
An object of this type is returned by :py:attr:`Vehicle.version`.
The version number can be read in a few different formats. To get it in a human-readable
format, just print `vehicle.version`. This might print something like "APM:Copter-3.3.2-rc4".
.. versionadded:: 2.0.3
.. py:attribute:: major
Major version number (integer).
.. py:attribute::minor
Minor version number (integer).
.. py:attribute:: patch
Patch version number (integer).
.. py:attribute:: release
Release type (integer). See the enum `FIRMWARE_VERSION_TYPE <http://mavlink.org/messages/common#http://mavlink.org/messages/common#FIRMWARE_VERSION_TYPE_DEV>`_.
This is a composite of the product release cycle stage (rc, beta etc) and the version in that cycle - e.g. 23.
"""
def __init__(self, raw_version, autopilot_type, vehicle_type):
self.autopilot_type = autopilot_type
self.vehicle_type = vehicle_type
self.raw_version = raw_version
if raw_version is None:
self.major = None
self.minor = None
self.patch = None
self.release = None
else:
self.major = raw_version >> 24 & 0xFF
self.minor = raw_version >> 16 & 0xFF
self.patch = raw_version >> 8 & 0xFF
self.release = raw_version & 0xFF
def is_stable(self):
"""
Returns True if the autopilot reports that the current firmware is a stable
release (not a pre-release or development version).
"""
return self.release == 255
def release_version(self):
"""
Returns the version within the release type (an integer).
This method returns "23" for Copter-3.3rc23.
"""
if self.release is None:
return None
if self.release == 255:
return 0
return self.release % 64
def release_type(self):
"""
Returns text describing the release type e.g. "alpha", "stable" etc.
"""
if self.release is None:
return None
types = ["dev", "alpha", "beta", "rc"]
return types[self.release >> 6]
def __str__(self):
prefix = ""
if self.autopilot_type == mavutil.mavlink.MAV_AUTOPILOT_ARDUPILOTMEGA:
prefix += "APM:"
elif self.autopilot_type == mavutil.mavlink.MAV_AUTOPILOT_PX4:
prefix += "PX4"
else:
prefix += "UnknownAutoPilot"
if self.vehicle_type == mavutil.mavlink.MAV_TYPE_QUADROTOR:
prefix += "Copter-"
elif self.vehicle_type == mavutil.mavlink.MAV_TYPE_FIXED_WING:
prefix += "Plane-"
elif self.vehicle_type == mavutil.mavlink.MAV_TYPE_GROUND_ROVER:
prefix += "Rover-"
else:
prefix += "UnknownVehicleType%d-" % self.vehicle_type
if self.release_type() is None:
release_type = "UnknownReleaseType"
elif self.is_stable():
release_type = ""
else:
# e.g. "-rc23"
release_type = "-" + str(self.release_type()) + str(self.release_version())
return prefix + "%s.%s.%s" % (self.major, self.minor, self.patch) + release_type
class Capabilities:
"""
Autopilot capabilities (supported message types and functionality).
An object of this type is returned by :py:attr:`Vehicle.capabilities`.
See the enum
`MAV_PROTOCOL_CAPABILITY <http://mavlink.org/messages/common#MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT>`_.
.. versionadded:: 2.0.3
.. py:attribute:: mission_float
Autopilot supports MISSION float message type (Boolean).
.. py:attribute:: param_float
Autopilot supports the PARAM float message type (Boolean).
.. py:attribute:: mission_int
Autopilot supports MISSION_INT scaled integer message type (Boolean).
.. py:attribute:: command_int
Autopilot supports COMMAND_INT scaled integer message type (Boolean).
.. py:attribute:: param_union
Autopilot supports the PARAM_UNION message type (Boolean).
.. py:attribute:: ftp
Autopilot supports ftp for file transfers (Boolean).
.. py:attribute:: set_attitude_target
Autopilot supports commanding attitude offboard (Boolean).
.. py:attribute:: set_attitude_target_local_ned
Autopilot supports commanding position and velocity targets in local NED frame (Boolean).
.. py:attribute:: set_altitude_target_global_int
Autopilot supports commanding position and velocity targets in global scaled integers (Boolean).
.. py:attribute:: terrain
Autopilot supports terrain protocol / data handling (Boolean).
.. py:attribute:: set_actuator_target
Autopilot supports direct actuator control (Boolean).
.. py:attribute:: flight_termination
Autopilot supports the flight termination command (Boolean).
.. py:attribute:: compass_calibration
Autopilot supports onboard compass calibration (Boolean).
"""
def __init__(self, capabilities):
self.mission_float = (((capabilities >> 0) & 1) == 1)
self.param_float = (((capabilities >> 1) & 1) == 1)
self.mission_int = (((capabilities >> 2) & 1) == 1)
self.command_int = (((capabilities >> 3) & 1) == 1)
self.param_union = (((capabilities >> 4) & 1) == 1)
self.ftp = (((capabilities >> 5) & 1) == 1)
self.set_attitude_target = (((capabilities >> 6) & 1) == 1)
self.set_attitude_target_local_ned = (((capabilities >> 7) & 1) == 1)
self.set_altitude_target_global_int = (((capabilities >> 8) & 1) == 1)
self.terrain = (((capabilities >> 9) & 1) == 1)
self.set_actuator_target = (((capabilities >> 10) & 1) == 1)
self.flight_termination = (((capabilities >> 11) & 1) == 1)
self.compass_calibration = (((capabilities >> 12) & 1) == 1)
class VehicleMode(object):
"""
This object is used to get and set the current "flight mode".
The flight mode determines the behaviour of the vehicle and what commands it can obey.
The recommended flight modes for *DroneKit-Python* apps depend on the vehicle type:
* Copter apps should use ``AUTO`` mode for "normal" waypoint missions and ``GUIDED`` mode otherwise.
* Plane and Rover apps should use the ``AUTO`` mode in all cases, re-writing the mission commands if "dynamic"
behaviour is required (they support only a limited subset of commands in ``GUIDED`` mode).
* Some modes like ``RETURN_TO_LAUNCH`` can be used on all platforms. Care should be taken
when using manual modes as these may require remote control input from the user.
The available set of supported flight modes is vehicle-specific (see
`Copter Modes <http://copter.ardupilot.com/wiki/flying-arducopter/flight-modes/>`_,
`Plane Modes <http://plane.ardupilot.com/wiki/flying/flight-modes/>`_,
`Rover Modes <http://rover.ardupilot.com/wiki/configuration-2/#mode_meanings>`_). If an unsupported mode is set the script
will raise a ``KeyError`` exception.
The :py:attr:`Vehicle.mode` attribute can be queried for the current mode.
The code snippet below shows how to observe changes to the mode and then read the value:
.. code:: python
#Callback definition for mode observer
def mode_callback(self, attr_name):
print "Vehicle Mode", self.mode
#Add observer callback for attribute `mode`
vehicle.add_attribute_listener('mode', mode_callback)
The code snippet below shows how to change the vehicle mode to AUTO:
.. code:: python
# Set the vehicle into auto mode
vehicle.mode = VehicleMode("AUTO")
For more information on getting/setting/observing the :py:attr:`Vehicle.mode`
(and other attributes) see the :ref:`attributes guide <vehicle_state_attributes>`.
.. py:attribute:: name
The mode name, as a ``string``.
"""
def __init__(self, name):
self.name = name
def __str__(self):
return "VehicleMode:%s" % self.name
def __eq__(self, other):
return self.name == other
def __ne__(self, other):
return self.name != other
class SystemStatus(object):
"""
This object is used to get and set the current "system status".
An object of this type is returned by :py:attr:`Vehicle.system_status`.
.. py:attribute:: state
The system state, as a ``string``.
"""
def __init__(self, state):
self.state = state
def __str__(self):
return "SystemStatus:%s" % self.state
def __eq__(self, other):
return self.state == other
def __ne__(self, other):
return self.state != other
class HasObservers(object):
def __init__(self):
logging.basicConfig()
self._logger = logging.getLogger(__name__)
# A mapping from attr_name to a list of observers
self._attribute_listeners = {}
self._attribute_cache = {}
def add_attribute_listener(self, attr_name, observer):
"""
Add an attribute listener callback.
The callback function (``observer``) is invoked differently depending on the *type of attribute*.
Attributes that represent sensor values or which are used to monitor connection status are updated
whenever a message is received from the vehicle. Attributes which reflect vehicle "state" are
only updated when their values change (for example :py:attr:`Vehicle.system_status`,
:py:attr:`Vehicle.armed`, and :py:attr:`Vehicle.mode`).
The callback can be removed using :py:func:`remove_attribute_listener`.
.. note::
The :py:func:`on_attribute` decorator performs the same operation as this method, but with
a more elegant syntax. Use ``add_attribute_listener`` by preference if you will need to remove
the observer.
The argument list for the callback is ``observer(object, attr_name, attribute_value)``:
* ``self`` - the associated :py:class:`Vehicle`. This may be compared to a global vehicle handle
to implement vehicle-specific callback handling (if needed).
* ``attr_name`` - the attribute name. This can be used to infer which attribute has triggered
if the same callback is used for watching several attributes.
* ``value`` - the attribute value (so you don't need to re-query the vehicle object).
The example below shows how to get callbacks for (global) location changes:
.. code:: python
#Callback to print the location in global frame
def location_callback(self, attr_name, msg):
print "Location (Global): ", msg
#Add observer for the vehicle's current location
vehicle.add_attribute_listener('global_frame', location_callback)
See :ref:`vehicle_state_observe_attributes` for more information.
:param String attr_name: The name of the attribute to watch (or '*' to watch all attributes).
:param observer: The callback to invoke when a change in the attribute is detected.
"""
listeners_for_attr = self._attribute_listeners.get(attr_name)
if listeners_for_attr is None:
listeners_for_attr = []
self._attribute_listeners[attr_name] = listeners_for_attr
if observer not in listeners_for_attr:
listeners_for_attr.append(observer)
def remove_attribute_listener(self, attr_name, observer):
"""
Remove an attribute listener (observer) that was previously added using :py:func:`add_attribute_listener`.
For example, the following line would remove a previously added vehicle 'global_frame'
observer called ``location_callback``:
.. code:: python
vehicle.remove_attribute_listener('global_frame', location_callback)
See :ref:`vehicle_state_observe_attributes` for more information.
:param String attr_name: The attribute name that is to have an observer removed (or '*' to remove an 'all attribute' observer).
:param observer: The callback function to remove.
"""
listeners_for_attr = self._attribute_listeners.get(attr_name)
if listeners_for_attr is not None:
listeners_for_attr.remove(observer)
if len(listeners_for_attr) == 0:
del self._attribute_listeners[attr_name]
def notify_attribute_listeners(self, attr_name, value, cache=False):
"""
This method is used to update attribute observers when the named attribute is updated.
You should call it in your message listeners after updating an attribute with
information from a vehicle message.
By default the value of ``cache`` is ``False`` and every update from the vehicle is sent to listeners
(whether or not the attribute has changed). This is appropriate for attributes which represent sensor
or heartbeat-type monitoring.
Set ``cache=True`` to update listeners only when the value actually changes (cache the previous
attribute value). This should be used where clients will only ever need to know the value when it has
changed. For example, this setting has been used for notifying :py:attr:`mode` changes.
See :ref:`example_create_attribute` for more information.
:param String attr_name: The name of the attribute that has been updated.
:param value: The current value of the attribute that has been updated.
:param Boolean cache: Set ``True`` to only notify observers when the attribute value changes.
"""
# Cached values are not re-sent if they are unchanged.
if cache:
if self._attribute_cache.get(attr_name) == value:
return
self._attribute_cache[attr_name] = value
# Notify observers.
for fn in self._attribute_listeners.get(attr_name, []):
try:
fn(self, attr_name, value)
except Exception:
self._logger.exception('Exception in attribute handler for %s' % attr_name, exc_info=True)
for fn in self._attribute_listeners.get('*', []):
try:
fn(self, attr_name, value)
except Exception:
self._logger.exception('Exception in attribute handler for %s' % attr_name, exc_info=True)
def on_attribute(self, name):
"""
Decorator for attribute listeners.
The decorated function (``observer``) is invoked differently depending on the *type of attribute*.
Attributes that represent sensor values or which are used to monitor connection status are updated
whenever a message is received from the vehicle. Attributes which reflect vehicle "state" are
only updated when their values change (for example :py:func:`Vehicle.system_status`,
:py:attr:`Vehicle.armed`, and :py:attr:`Vehicle.mode`).
The argument list for the callback is ``observer(object, attr_name, attribute_value)``
* ``self`` - the associated :py:class:`Vehicle`. This may be compared to a global vehicle handle
to implement vehicle-specific callback handling (if needed).
* ``attr_name`` - the attribute name. This can be used to infer which attribute has triggered
if the same callback is used for watching several attributes.
* ``msg`` - the attribute value (so you don't need to re-query the vehicle object).
.. note::
There is no way to remove an attribute listener added with this decorator. Use
:py:func:`add_attribute_listener` if you need to be able to remove
the :py:func:`attribute listener <remove_attribute_listener>`.
The code fragment below shows how you can create a listener for the attitude attribute.
.. code:: python
@vehicle.on_attribute('attitude')
def attitude_listener(self, name, msg):
print '%s attribute is: %s' % (name, msg)
See :ref:`vehicle_state_observe_attributes` for more information.
:param String name: The name of the attribute to watch (or '*' to watch all attributes).
:param observer: The callback to invoke when a change in the attribute is detected.
"""
def decorator(fn):
if isinstance(name, list):
for n in name:
self.add_attribute_listener(n, fn)
else:
self.add_attribute_listener(name, fn)
return decorator
class ChannelsOverride(dict):
"""
A dictionary class for managing Vehicle channel overrides.
Channels can be read, written, or cleared by index or using a dictionary syntax.
To clear a value, set it to ``None`` or use ``del`` on the item.
An object of this type is returned by :py:attr:`Vehicle.channels.overrides <Channels.overrides>`.
For more information and examples see :ref:`example_channel_overrides`.
"""
def __init__(self, vehicle):
self._vehicle = vehicle
self._count = 8 # Fixed by MAVLink
self._active = True
def __getitem__(self, key):
return dict.__getitem__(self, str(key))
def __setitem__(self, key, value):
if not (0 < int(key) <= self._count):
raise KeyError('Invalid channel index %s' % key)
if not value:
try:
dict.__delitem__(self, str(key))
except:
pass
else:
dict.__setitem__(self, str(key), value)
self._send()
def __delitem__(self, key):
dict.__delitem__(self, str(key))
self._send()
def __len__(self):
return self._count
def _send(self):
if self._active:
overrides = [0] * 8
for k, v in self.items():
overrides[int(k) - 1] = v
self._vehicle._master.mav.rc_channels_override_send(0, 0, *overrides)
class Channels(dict):
"""
A dictionary class for managing RC channel information associated with a :py:class:`Vehicle`.
An object of this type is accessed through :py:attr:`Vehicle.channels`. This object also stores
the current vehicle channel overrides through its :py:attr:`overrides` attribute.
For more information and examples see :ref:`example_channel_overrides`.
"""
def __init__(self, vehicle, count):
self._vehicle = vehicle
self._count = count
self._overrides = ChannelsOverride(vehicle)
# populate readback
self._readonly = False
for k in range(0, count):
self[k + 1] = None
self._readonly = True
@property
def count(self):
"""
The number of channels defined in the dictionary (currently 8).
"""
return self._count
def __getitem__(self, key):
return dict.__getitem__(self, str(key))
def __setitem__(self, key, value):
if self._readonly:
raise TypeError('__setitem__ is not supported on Channels object')
return dict.__setitem__(self, str(key), value)
def __len__(self):
return self._count
def _update_channel(self, channel, value):
# If we have channels on different ports, we expand the Channels
# object to support them.
channel = int(channel)
self._readonly = False
self[channel] = value
self._readonly = True
self._count = max(self._count, channel)
@property
def overrides(self):
"""
Attribute to read, set and clear channel overrides (also known as "rc overrides")
associated with a :py:class:`Vehicle` (via :py:class:`Vehicle.channels`). This is an
object of type :py:class:`ChannelsOverride`.
For more information and examples see :ref:`example_channel_overrides`.
To set channel overrides:
.. code:: python
# Set and clear overrids using dictionary syntax (clear by setting override to none)
vehicle.channels.overrides = {'5':None, '6':None,'3':500}
# You can also set and clear overrides using indexing syntax
vehicle.channels.overrides['2'] = 200
vehicle.channels.overrides['2'] = None
# Clear using 'del'
del vehicle.channels.overrides['3']
# Clear all overrides by setting an empty dictionary
vehicle.channels.overrides = {}
Read the channel overrides either as a dictionary or by index. Note that you'll get
a ``KeyError`` exception if you read a channel override that has not been set.
.. code:: python
# Get all channel overrides
print " Channel overrides: %s" % vehicle.channels.overrides
# Print just one channel override
print " Ch2 override: %s" % vehicle.channels.overrides['2']
"""
return self._overrides
@overrides.setter
def overrides(self, newch):
self._overrides._active = False
self._overrides.clear()
for k, v in newch.items():
if v:
self._overrides[str(k)] = v
else:
try:
del self._overrides[str(k)]
except:
pass
self._overrides._active = True
self._overrides._send()
class Locations(HasObservers):
"""
An object for holding location information in global, global relative and local frames.
:py:class:`Vehicle` owns an object of this type. See :py:attr:`Vehicle.location` for information on
reading and observing location in the different frames.
The different frames are accessed through the members, which are created with this object.
They can be read, and are observable.
"""
def __init__(self, vehicle):
super(Locations, self).__init__()
self._lat = None
self._lon = None
self._alt = None
self._relative_alt = None
@vehicle.on_message('GLOBAL_POSITION_INT')
def listener(vehicle, name, m):
(self._lat, self._lon) = (m.lat / 1.0e7, m.lon / 1.0e7)
self._relative_alt = m.relative_alt / 1000.0
self.notify_attribute_listeners('global_relative_frame', self.global_relative_frame)
vehicle.notify_attribute_listeners('location.global_relative_frame',
vehicle.location.global_relative_frame)
if self._alt is not None or m.alt != 0:
# Require first alt value to be non-0
# TODO is this the proper check to do?
self._alt = m.alt / 1000.0
self.notify_attribute_listeners('global_frame', self.global_frame)
vehicle.notify_attribute_listeners('location.global_frame',
vehicle.location.global_frame)
vehicle.notify_attribute_listeners('location', vehicle.location)
self._north = None
self._east = None
self._down = None
@vehicle.on_message('LOCAL_POSITION_NED')
def listener(vehicle, name, m):
self._north = m.x
self._east = m.y
self._down = m.z
self.notify_attribute_listeners('local_frame', self.local_frame)
vehicle.notify_attribute_listeners('location.local_frame', vehicle.location.local_frame)
vehicle.notify_attribute_listeners('location', vehicle.location)
@property
def local_frame(self):
"""
Location in local NED frame (a :py:class:`LocationGlobalRelative`).
This is accessed through the :py:attr:`Vehicle.location` attribute:
.. code-block:: python
print "Local Location: %s" % vehicle.location.local_frame
This location will not start to update until the vehicle is armed.
"""
return LocationLocal(self._north, self._east, self._down)
@property
def global_frame(self):
"""
Location in global frame (a :py:class:`LocationGlobal`).
The latitude and longitude are relative to the
`WGS84 coordinate system <http://en.wikipedia.org/wiki/World_Geodetic_System>`_.
The altitude is relative to mean sea-level (MSL).
This is accessed through the :py:attr:`Vehicle.location` attribute:
.. code-block:: python
print "Global Location: %s" % vehicle.location.global_frame
print "Sea level altitude is: %s" % vehicle.location.global_frame.alt
Its ``lat`` and ``lon`` attributes are populated shortly after GPS becomes available.
The ``alt`` can take several seconds longer to populate (from the barometer).
Listeners are not notified of changes to this attribute until it has fully populated.
To watch for changes you can use :py:func:`Vehicle.on_attribute` decorator or
:py:func:`add_attribute_listener` (decorator approach shown below):
.. code-block:: python
@vehicle.on_attribute('location.global_frame')
def listener(self, attr_name, value):
print " Global: %s" % value
#Alternatively, use decorator: ``@vehicle.location.on_attribute('global_frame')``.
"""
return LocationGlobal(self._lat, self._lon, self._alt)
@property
def global_relative_frame(self):
"""
Location in global frame, with altitude relative to the home location
(a :py:class:`LocationGlobalRelative`).
The latitude and longitude are relative to the
`WGS84 coordinate system <http://en.wikipedia.org/wiki/World_Geodetic_System>`_.
The altitude is relative to :py:attr:`home location <Vehicle.home_location>`.
This is accessed through the :py:attr:`Vehicle.location` attribute:
.. code-block:: python
print "Global Location (relative altitude): %s" % vehicle.location.global_relative_frame
print "Altitude relative to home_location: %s" % vehicle.location.global_relative_frame.alt
"""
return LocationGlobalRelative(self._lat, self._lon, self._relative_alt)
class Vehicle(HasObservers):
"""
The main vehicle API.