Skip to content

Commit 07d7503

Browse files
committed
Merge pull request #148 from hamishwillee/tmp-battery-docs
Tidy documentation for addition of Battery class
2 parents 0b7c2be + bbf7d95 commit 07d7503

File tree

3 files changed

+51
-50
lines changed

3 files changed

+51
-50
lines changed

docs/examples/vehicle_state.rst

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -38,9 +38,10 @@ On the *MAVProxy* console you should see (something like):
3838
Location: Attitude: Attitude:pitch=-0.00405988190323,yaw=-0.0973932668567,roll=-0.00393210304901
3939
Velocity: [0.06, -0.07, 0.0]
4040
GPS: GPSInfo:fix=3,num_sat=10
41-
groundspeed: 0.0
42-
airspeed: 0.0
43-
mount_status: [None, None, None]
41+
Groundspeed: 0.0
42+
Airspeed: 0.0
43+
Mount status: [None, None, None]
44+
Battery: Battery voltage: 12590, current: 0, level: 99
4445
Mode: STABILIZE
4546
Armed: False
4647
Set Vehicle.mode=GUIDED (currently: STABILIZE)

droneapi/lib/__init__.py

Lines changed: 43 additions & 44 deletions
Original file line numberDiff line numberDiff line change
@@ -171,7 +171,7 @@ def __str__(self):
171171

172172
class Battery(object):
173173
"""
174-
Battery info available
174+
System battery information.
175175
176176
:param voltage: Battery voltage in millivolts.
177177
:param current: Battery current, in 10 * milliamperes. ``None`` if the autopilot does not support current measurement.
@@ -194,7 +194,7 @@ def __str__(self):
194194

195195
class VehicleMode(object):
196196
"""
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".
198198
199199
The flight mode determines the behaviour of the vehicle and what commands it can obey.
200200
The recommended flight modes for *DroneKit-Python* apps depend on the vehicle type:
@@ -322,7 +322,6 @@ def location_callback(location):
322322
print "Location: ", vehicle.location
323323
324324
325-
326325
.. note::
327326
Attribute changes will only be published for changes due to some other entity.
328327
They will not be published for changes made by the local API client
@@ -331,7 +330,7 @@ def location_callback(location):
331330
:param attr_name: The attribute to watch.
332331
:param observer: The callback to invoke when a change in the attribute is detected.
333332
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
335334
"""
336335
l = self.__observers.get(attr_name)
337336
if l is None:
@@ -457,17 +456,22 @@ class Vehicle(HasObservers):
457456
458457
.. py:attribute:: mount_status
459458
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 ]``.
461460
462461
The values in the list are set to ``None`` if no mount is configured.
463462
464463
464+
.. py:attribute:: battery
465+
466+
Current system :py:class:`Battery` status.
467+
468+
465469
.. py:attribute:: channel_override
466470
467471
.. warning::
468472
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!
471475
472476
Instead use the appropriate MAVLink commands like DO_SET_SERVO/DO_SET_RELAY, or more generally
473477
set the desired position or direction/speed.
@@ -477,15 +481,15 @@ class Vehicle(HasObservers):
477481
478482
To cancel an override call ``channel_override`` again, setting zero for the overridden channels.
479483
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>`_ ,
483487
`Rover <http://rover.ardupilot.com/wiki/apmrover2-parameters/#rcmap__parameters>`_).
484488
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
489493
controlled by normal autopilot code).
490494
491495
An example of setting and clearing the override is given below:
@@ -510,8 +514,8 @@ class Vehicle(HasObservers):
510514
511515
https://github.com/diydrones/dronekit-python/issues/72
512516
513-
.. todo::
514-
517+
.. todo::
518+
515519
channel_override/channel_readback documentation
516520
517521
In a future update strings will be defined per vehicle type ('pitch', 'yaw', 'roll' etc...)
@@ -544,8 +548,6 @@ class Vehicle(HasObservers):
544548
545549
.. todo:: In V2, there may be ardupilot specific attributes & types (as in the introduction). If so, text below might be useful.
546550
547-
(see `client_sketch.py#L76 <https://github.com/diydrones/dronekit-python/blob/master/examples/sketch/client_sketch.py#L76>`_)
548-
549551
**Autopilot specific attributes & types:**
550552
551553
.. py:attribute:: ap_pin5_mode
@@ -556,7 +558,6 @@ class Vehicle(HasObservers):
556558
557559
? double (0, 1, 2.3 etc...)
558560
559-
.. todo:: Add battery and charge information if this is closed: https://github.com/diydrones/dronekit-python/issues/102
560561
561562
.. todo:: Add waypoint_home attribute IF this is added: https://github.com/diydrones/dronekit-python/issues/105
562563
@@ -571,9 +572,9 @@ def commands(self):
571572
"""
572573
Gets the editable waypoints for this vehicle (the current "mission").
573574
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+
577578
:returns: A :py:class:`CommandSequence` containing the waypoints for this vehicle.
578579
"""
579580
None
@@ -602,10 +603,9 @@ def get_mission(self, query_params):
602603
603604
Returns an object providing access to historical missions.
604605
605-
.. warning::
606+
.. warning::
606607
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
609609
610610
:param query_params: Some set of arguments that can be used to find a past mission
611611
:return: Mission - the mission object.
@@ -639,7 +639,7 @@ def message_factory(self):
639639
msg = vehicle.message_factory.image_trigger_control_encode(True)
640640
vehicle.send_mavlink(msg)
641641
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
643643
API will set these appropriately when the message is sent.
644644
645645
.. todo:: When I have a custom message guide topic. Link from here to it.
@@ -655,7 +655,7 @@ def send_mavlink(self, message):
655655
The function can send arbitrary messages/commands to a vehicle at any time and in any vehicle mode. It is particularly useful for
656656
controlling vehicles outside of missions (for example, in GUIDED mode).
657657
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.
659659
Callers do not need to populate sysId/componentId/crc in the packet as the method will take care of that before sending.
660660
661661
: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):
677677
678678
The code snippet below shows how to set a "demo" callback function as the callback handler:
679679
680-
.. code:: python
680+
.. code:: python
681681
682682
# Demo callback handler for raw MAVLink messages
683683
def mavrx_debug_handler(message):
@@ -754,12 +754,12 @@ class Parameters(HasObservers):
754754
vehicle.parameters['THR_MIN']=100
755755
vehicle.flush()
756756
757-
.. note::
757+
.. note::
758758
759759
At time of writing ``Parameters`` does not implement the observer methods, and change notification for parameters
760760
is not supported.
761761
762-
.. todo::
762+
.. todo::
763763
764764
Check to see if observers have been implemented and if so, update the information here, in about, and in Vehicle class:
765765
https://github.com/diydrones/dronekit-python/issues/107
@@ -780,9 +780,9 @@ class Command(mavutil.mavlink.MAVLink_mission_item_message):
780780
mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, 0, 0, 0, 0, 0,-34.364114, 149.166022, 30)
781781
782782
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
786786
(for example, the camera). Set to zero (broadcast) in most cases.
787787
:param seq: The sequence number within the mission (the autopilot will reject messages sent out of sequence).
788788
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):
845845
0, 0, 0, 0, 0, 0,
846846
lat, lon, altitude)
847847
cmds.add(cmd)
848-
vehicle.flush()
849-
848+
vehicle.flush()
850849
851850
.. py:function:: takeoff(altitude)
852851
@@ -871,18 +870,18 @@ class CommandSequence(object):
871870

872871
def download(self):
873872
'''
874-
Download all waypoints from the vehicle.
873+
Download all waypoints from the vehicle.
875874
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+
'''
878877
pass
879878

880879
def wait_valid(self):
881880
'''
882-
Block the calling thread until waypoints have been downloaded.
881+
Block the calling thread until waypoints have been downloaded.
883882
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+
'''
886885
pass
887886

888887

@@ -921,10 +920,10 @@ def add(self, cmd):
921920
@property
922921
def count(self):
923922
'''
924-
Return number of waypoints.
923+
Return number of waypoints.
925924
926-
:return: The number of waypoints in the sequence.
927-
'''
925+
:return: The number of waypoints in the sequence.
926+
'''
928927
return 0
929928

930929
@property

examples/vehicle_state/vehicle_state.py

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -22,9 +22,10 @@
2222
print " Attitude: %s" % v.attitude
2323
print " Velocity: %s" % v.velocity
2424
print " GPS: %s" % v.gps_0
25-
print " groundspeed: %s" % v.groundspeed
26-
print " airspeed: %s" % v.airspeed
27-
print " mount_status: %s" % v.mount_status
25+
print " Groundspeed: %s" % v.groundspeed
26+
print " Airspeed: %s" % v.airspeed
27+
print " Mount status: %s" % v.mount_status
28+
print " Battery: %s" % v.battery
2829
print " Mode: %s" % v.mode.name # settable
2930
print " Armed: %s" % v.armed # settable
3031

0 commit comments

Comments
 (0)