@@ -171,7 +171,7 @@ def __str__(self):
171
171
172
172
class Battery (object ):
173
173
"""
174
- Battery info available
174
+ System battery information.
175
175
176
176
:param voltage: Battery voltage in millivolts.
177
177
:param current: Battery current, in 10 * milliamperes. ``None`` if the autopilot does not support current measurement.
@@ -194,7 +194,7 @@ def __str__(self):
194
194
195
195
class VehicleMode (object ):
196
196
"""
197
- This object is used to get and set the current "flight mode".
197
+ This object is used to get and set the current "flight mode".
198
198
199
199
The flight mode determines the behaviour of the vehicle and what commands it can obey.
200
200
The recommended flight modes for *DroneKit-Python* apps depend on the vehicle type:
@@ -322,7 +322,6 @@ def location_callback(location):
322
322
print "Location: ", vehicle.location
323
323
324
324
325
-
326
325
.. note::
327
326
Attribute changes will only be published for changes due to some other entity.
328
327
They will not be published for changes made by the local API client
@@ -331,7 +330,7 @@ def location_callback(location):
331
330
:param attr_name: The attribute to watch.
332
331
:param observer: The callback to invoke when a change in the attribute is detected.
333
332
334
- .. todo:: Check that the defect for endless repetition after thread closes is fixed: https://github.com/diydrones/dronekit-python/issues/74
333
+ .. todo:: Check that the defect for endless repetition after thread closes is fixed: https://github.com/diydrones/dronekit-python/issues/74
335
334
"""
336
335
l = self .__observers .get (attr_name )
337
336
if l is None :
@@ -457,17 +456,22 @@ class Vehicle(HasObservers):
457
456
458
457
.. py:attribute:: mount_status
459
458
460
- Current status of the camera mount (gimbal) as a three element list: ``[ pitch, yaw, roll ]``.
459
+ Current status of the camera mount (gimbal) as a three element list: ``[ pitch, yaw, roll ]``.
461
460
462
461
The values in the list are set to ``None`` if no mount is configured.
463
462
464
463
464
+ .. py:attribute:: battery
465
+
466
+ Current system :py:class:`Battery` status.
467
+
468
+
465
469
.. py:attribute:: channel_override
466
470
467
471
.. warning::
468
472
469
- RC override may be useful for simulating user input and when implementing certain types of joystick control.
470
- It should not be used for direct control of vehicle channels unless there is no other choice!
473
+ RC override may be useful for simulating user input and when implementing certain types of joystick control.
474
+ It should not be used for direct control of vehicle channels unless there is no other choice!
471
475
472
476
Instead use the appropriate MAVLink commands like DO_SET_SERVO/DO_SET_RELAY, or more generally
473
477
set the desired position or direction/speed.
@@ -477,15 +481,15 @@ class Vehicle(HasObservers):
477
481
478
482
To cancel an override call ``channel_override`` again, setting zero for the overridden channels.
479
483
480
- The values of the first four channels map to the main flight controls: 1=Roll, 2=Pitch, 3=Throttle, 4=Yaw (the mapping is defined in ``RCMAP_`` parameters:
481
- `Plane <http://plane.ardupilot.com/wiki/arduplane-parameters/#rcmap__parameters>`_,
482
- `Copter <http://copter.ardupilot.com/wiki/configuration/arducopter-parameters/#rcmap__parameters>`_ ,
484
+ The values of the first four channels map to the main flight controls: 1=Roll, 2=Pitch, 3=Throttle, 4=Yaw (the mapping is defined in ``RCMAP_`` parameters:
485
+ `Plane <http://plane.ardupilot.com/wiki/arduplane-parameters/#rcmap__parameters>`_,
486
+ `Copter <http://copter.ardupilot.com/wiki/configuration/arducopter-parameters/#rcmap__parameters>`_ ,
483
487
`Rover <http://rover.ardupilot.com/wiki/apmrover2-parameters/#rcmap__parameters>`_).
484
488
485
- The remaining channel values are configurable, and their purpose can be determined using the
486
- `RCn_FUNCTION parameters <http://plane.ardupilot.com/wiki/flight-features/channel-output-functions/>`_.
487
- In general a value of 0 set for a specific ``RCn_FUNCTION`` indicates that the channel can be
488
- `mission controlled <http://plane.ardupilot.com/wiki/flight-features/channel-output-functions/#disabled>`_ (i.e. it will not directly be
489
+ The remaining channel values are configurable, and their purpose can be determined using the
490
+ `RCn_FUNCTION parameters <http://plane.ardupilot.com/wiki/flight-features/channel-output-functions/>`_.
491
+ In general a value of 0 set for a specific ``RCn_FUNCTION`` indicates that the channel can be
492
+ `mission controlled <http://plane.ardupilot.com/wiki/flight-features/channel-output-functions/#disabled>`_ (i.e. it will not directly be
489
493
controlled by normal autopilot code).
490
494
491
495
An example of setting and clearing the override is given below:
@@ -510,8 +514,8 @@ class Vehicle(HasObservers):
510
514
511
515
https://github.com/diydrones/dronekit-python/issues/72
512
516
513
- .. todo::
514
-
517
+ .. todo::
518
+
515
519
channel_override/channel_readback documentation
516
520
517
521
In a future update strings will be defined per vehicle type ('pitch', 'yaw', 'roll' etc...)
@@ -544,8 +548,6 @@ class Vehicle(HasObservers):
544
548
545
549
.. todo:: In V2, there may be ardupilot specific attributes & types (as in the introduction). If so, text below might be useful.
546
550
547
- (see `client_sketch.py#L76 <https://github.com/diydrones/dronekit-python/blob/master/examples/sketch/client_sketch.py#L76>`_)
548
-
549
551
**Autopilot specific attributes & types:**
550
552
551
553
.. py:attribute:: ap_pin5_mode
@@ -556,7 +558,6 @@ class Vehicle(HasObservers):
556
558
557
559
? double (0, 1, 2.3 etc...)
558
560
559
- .. todo:: Add battery and charge information if this is closed: https://github.com/diydrones/dronekit-python/issues/102
560
561
561
562
.. todo:: Add waypoint_home attribute IF this is added: https://github.com/diydrones/dronekit-python/issues/105
562
563
@@ -571,9 +572,9 @@ def commands(self):
571
572
"""
572
573
Gets the editable waypoints for this vehicle (the current "mission").
573
574
574
- This can be used to get, create, and modify a mission. It can also be used for direct control of vehicle position
575
- (outside missions) using the :py:func:`goto <droneapi.lib.CommandSequence.goto>` method.
576
-
575
+ This can be used to get, create, and modify a mission. It can also be used for direct control of vehicle position
576
+ (outside missions) using the :py:func:`goto <droneapi.lib.CommandSequence.goto>` method.
577
+
577
578
:returns: A :py:class:`CommandSequence` containing the waypoints for this vehicle.
578
579
"""
579
580
None
@@ -602,10 +603,9 @@ def get_mission(self, query_params):
602
603
603
604
Returns an object providing access to historical missions.
604
605
605
- .. warning::
606
+ .. warning::
606
607
607
- Mission objects are only accessible from the REST API in release 1 (most use-cases requiring missions prefer a
608
- REST interface). The :class:`Mission` class has an empty implementation in DroneKit-Python release 1.
608
+ Mission objects are only accessible from the REST API in release 1 (most use-cases requiring missions prefer a
609
609
610
610
:param query_params: Some set of arguments that can be used to find a past mission
611
611
:return: Mission - the mission object.
@@ -639,7 +639,7 @@ def message_factory(self):
639
639
msg = vehicle.message_factory.image_trigger_control_encode(True)
640
640
vehicle.send_mavlink(msg)
641
641
642
- There is no need to specify the system id, component id or sequence number of messages (if defined in the message type) as the
642
+ There is no need to specify the system id, component id or sequence number of messages (if defined in the message type) as the
643
643
API will set these appropriately when the message is sent.
644
644
645
645
.. todo:: When I have a custom message guide topic. Link from here to it.
@@ -655,7 +655,7 @@ def send_mavlink(self, message):
655
655
The function can send arbitrary messages/commands to a vehicle at any time and in any vehicle mode. It is particularly useful for
656
656
controlling vehicles outside of missions (for example, in GUIDED mode).
657
657
658
- The :py:func:`message_factory <droneapi.lib.Vehicle.message_factory>` is used to create messages in the appropriate format.
658
+ The :py:func:`message_factory <droneapi.lib.Vehicle.message_factory>` is used to create messages in the appropriate format.
659
659
Callers do not need to populate sysId/componentId/crc in the packet as the method will take care of that before sending.
660
660
661
661
:param: message: A ``MAVLink_message`` instance, created using :py:func:`message_factory <droneapi.lib.Vehicle.message_factory>`.
@@ -677,7 +677,7 @@ def set_mavlink_callback(self, callback):
677
677
678
678
The code snippet below shows how to set a "demo" callback function as the callback handler:
679
679
680
- .. code:: python
680
+ .. code:: python
681
681
682
682
# Demo callback handler for raw MAVLink messages
683
683
def mavrx_debug_handler(message):
@@ -754,12 +754,12 @@ class Parameters(HasObservers):
754
754
vehicle.parameters['THR_MIN']=100
755
755
vehicle.flush()
756
756
757
- .. note::
757
+ .. note::
758
758
759
759
At time of writing ``Parameters`` does not implement the observer methods, and change notification for parameters
760
760
is not supported.
761
761
762
- .. todo::
762
+ .. todo::
763
763
764
764
Check to see if observers have been implemented and if so, update the information here, in about, and in Vehicle class:
765
765
https://github.com/diydrones/dronekit-python/issues/107
@@ -780,9 +780,9 @@ class Command(mavutil.mavlink.MAVLink_mission_item_message):
780
780
mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, 0, 0, 0, 0, 0,-34.364114, 149.166022, 30)
781
781
782
782
783
- :param target_system: The id number of the message's target system (drone, GSC) within the MAVLink network.
784
- Set this to zero (broadcast) when communicating with a companion computer.
785
- :param target_component: The id of a component the message should be routed to within the target system
783
+ :param target_system: The id number of the message's target system (drone, GSC) within the MAVLink network.
784
+ Set this to zero (broadcast) when communicating with a companion computer.
785
+ :param target_component: The id of a component the message should be routed to within the target system
786
786
(for example, the camera). Set to zero (broadcast) in most cases.
787
787
:param seq: The sequence number within the mission (the autopilot will reject messages sent out of sequence).
788
788
This should be set to zero as the API will automatically set the correct value when uploading a mission.
@@ -845,8 +845,7 @@ class CommandSequence(object):
845
845
0, 0, 0, 0, 0, 0,
846
846
lat, lon, altitude)
847
847
cmds.add(cmd)
848
- vehicle.flush()
849
-
848
+ vehicle.flush()
850
849
851
850
.. py:function:: takeoff(altitude)
852
851
@@ -871,18 +870,18 @@ class CommandSequence(object):
871
870
872
871
def download (self ):
873
872
'''
874
- Download all waypoints from the vehicle.
873
+ Download all waypoints from the vehicle.
875
874
876
- The download is asynchronous. Use :py:func:`wait_valid()` to block your thread until the download is complete.
877
- '''
875
+ The download is asynchronous. Use :py:func:`wait_valid()` to block your thread until the download is complete.
876
+ '''
878
877
pass
879
878
880
879
def wait_valid (self ):
881
880
'''
882
- Block the calling thread until waypoints have been downloaded.
881
+ Block the calling thread until waypoints have been downloaded.
883
882
884
- This can be called after :py:func:`download()` to block the thread until the asynchronous download is complete.
885
- '''
883
+ This can be called after :py:func:`download()` to block the thread until the asynchronous download is complete.
884
+ '''
886
885
pass
887
886
888
887
@@ -921,10 +920,10 @@ def add(self, cmd):
921
920
@property
922
921
def count (self ):
923
922
'''
924
- Return number of waypoints.
923
+ Return number of waypoints.
925
924
926
- :return: The number of waypoints in the sequence.
927
- '''
925
+ :return: The number of waypoints in the sequence.
926
+ '''
928
927
return 0
929
928
930
929
@property
0 commit comments