Skip to content

Tidy documentation for addition of Battery class #148

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Merged
merged 1 commit into from
Jun 10, 2015
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
7 changes: 4 additions & 3 deletions docs/examples/vehicle_state.rst
Original file line number Diff line number Diff line change
Expand Up @@ -38,9 +38,10 @@ On the *MAVProxy* console you should see (something like):
Location: Attitude: Attitude:pitch=-0.00405988190323,yaw=-0.0973932668567,roll=-0.00393210304901
Velocity: [0.06, -0.07, 0.0]
GPS: GPSInfo:fix=3,num_sat=10
groundspeed: 0.0
airspeed: 0.0
mount_status: [None, None, None]
Groundspeed: 0.0
Airspeed: 0.0
Mount status: [None, None, None]
Battery: Battery voltage: 12590, current: 0, level: 99
Mode: STABILIZE
Armed: False
Set Vehicle.mode=GUIDED (currently: STABILIZE)
Expand Down
87 changes: 43 additions & 44 deletions droneapi/lib/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -171,7 +171,7 @@ def __str__(self):

class Battery(object):
"""
Battery info available
System battery information.

:param voltage: Battery voltage in millivolts.
:param current: Battery current, in 10 * milliamperes. ``None`` if the autopilot does not support current measurement.
Expand All @@ -194,7 +194,7 @@ def __str__(self):

class VehicleMode(object):
"""
This object is used to get and set the current "flight mode".
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:
Expand Down Expand Up @@ -322,7 +322,6 @@ def location_callback(location):
print "Location: ", vehicle.location



.. note::
Attribute changes will only be published for changes due to some other entity.
They will not be published for changes made by the local API client
Expand All @@ -331,7 +330,7 @@ def location_callback(location):
:param attr_name: The attribute to watch.
:param observer: The callback to invoke when a change in the attribute is detected.

.. todo:: Check that the defect for endless repetition after thread closes is fixed: https://github.com/diydrones/dronekit-python/issues/74
.. todo:: Check that the defect for endless repetition after thread closes is fixed: https://github.com/diydrones/dronekit-python/issues/74
"""
l = self.__observers.get(attr_name)
if l is None:
Expand Down Expand Up @@ -457,17 +456,22 @@ class Vehicle(HasObservers):

.. py:attribute:: mount_status

Current status of the camera mount (gimbal) as a three element list: ``[ pitch, yaw, roll ]``.
Current status of the camera mount (gimbal) as a three element list: ``[ pitch, yaw, roll ]``.

The values in the list are set to ``None`` if no mount is configured.


.. py:attribute:: battery

Current system :py:class:`Battery` status.


.. py:attribute:: channel_override

.. warning::

RC override may be useful for simulating user input and when implementing certain types of joystick control.
It should not be used for direct control of vehicle channels unless there is no other choice!
RC override may be useful for simulating user input and when implementing certain types of joystick control.
It should not be used for direct control of vehicle channels unless there is no other choice!

Instead use the appropriate MAVLink commands like DO_SET_SERVO/DO_SET_RELAY, or more generally
set the desired position or direction/speed.
Expand All @@ -477,15 +481,15 @@ class Vehicle(HasObservers):

To cancel an override call ``channel_override`` again, setting zero for the overridden channels.

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:
`Plane <http://plane.ardupilot.com/wiki/arduplane-parameters/#rcmap__parameters>`_,
`Copter <http://copter.ardupilot.com/wiki/configuration/arducopter-parameters/#rcmap__parameters>`_ ,
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:
`Plane <http://plane.ardupilot.com/wiki/arduplane-parameters/#rcmap__parameters>`_,
`Copter <http://copter.ardupilot.com/wiki/configuration/arducopter-parameters/#rcmap__parameters>`_ ,
`Rover <http://rover.ardupilot.com/wiki/apmrover2-parameters/#rcmap__parameters>`_).

The remaining channel values are configurable, and their purpose can be determined using the
`RCn_FUNCTION parameters <http://plane.ardupilot.com/wiki/flight-features/channel-output-functions/>`_.
In general a value of 0 set for a specific ``RCn_FUNCTION`` indicates that the channel can be
`mission controlled <http://plane.ardupilot.com/wiki/flight-features/channel-output-functions/#disabled>`_ (i.e. it will not directly be
The remaining channel values are configurable, and their purpose can be determined using the
`RCn_FUNCTION parameters <http://plane.ardupilot.com/wiki/flight-features/channel-output-functions/>`_.
In general a value of 0 set for a specific ``RCn_FUNCTION`` indicates that the channel can be
`mission controlled <http://plane.ardupilot.com/wiki/flight-features/channel-output-functions/#disabled>`_ (i.e. it will not directly be
controlled by normal autopilot code).

An example of setting and clearing the override is given below:
Expand All @@ -510,8 +514,8 @@ class Vehicle(HasObservers):

https://github.com/diydrones/dronekit-python/issues/72

.. todo::

.. todo::
channel_override/channel_readback documentation

In a future update strings will be defined per vehicle type ('pitch', 'yaw', 'roll' etc...)
Expand Down Expand Up @@ -544,8 +548,6 @@ class Vehicle(HasObservers):

.. todo:: In V2, there may be ardupilot specific attributes & types (as in the introduction). If so, text below might be useful.

(see `client_sketch.py#L76 <https://github.com/diydrones/dronekit-python/blob/master/examples/sketch/client_sketch.py#L76>`_)

**Autopilot specific attributes & types:**

.. py:attribute:: ap_pin5_mode
Expand All @@ -556,7 +558,6 @@ class Vehicle(HasObservers):

? double (0, 1, 2.3 etc...)

.. todo:: Add battery and charge information if this is closed: https://github.com/diydrones/dronekit-python/issues/102

.. todo:: Add waypoint_home attribute IF this is added: https://github.com/diydrones/dronekit-python/issues/105

Expand All @@ -571,9 +572,9 @@ def commands(self):
"""
Gets the editable waypoints for this vehicle (the current "mission").

This can be used to get, create, and modify a mission. It can also be used for direct control of vehicle position
(outside missions) using the :py:func:`goto <droneapi.lib.CommandSequence.goto>` method.

This can be used to get, create, and modify a mission. It can also be used for direct control of vehicle position
(outside missions) using the :py:func:`goto <droneapi.lib.CommandSequence.goto>` method.
:returns: A :py:class:`CommandSequence` containing the waypoints for this vehicle.
"""
None
Expand Down Expand Up @@ -602,10 +603,9 @@ def get_mission(self, query_params):

Returns an object providing access to historical missions.

.. warning::
.. warning::

Mission objects are only accessible from the REST API in release 1 (most use-cases requiring missions prefer a
REST interface). The :class:`Mission` class has an empty implementation in DroneKit-Python release 1.
Mission objects are only accessible from the REST API in release 1 (most use-cases requiring missions prefer a

:param query_params: Some set of arguments that can be used to find a past mission
:return: Mission - the mission object.
Expand Down Expand Up @@ -639,7 +639,7 @@ def message_factory(self):
msg = vehicle.message_factory.image_trigger_control_encode(True)
vehicle.send_mavlink(msg)

There is no need to specify the system id, component id or sequence number of messages (if defined in the message type) as the
There is no need to specify the system id, component id or sequence number of messages (if defined in the message type) as the
API will set these appropriately when the message is sent.

.. todo:: When I have a custom message guide topic. Link from here to it.
Expand All @@ -655,7 +655,7 @@ def send_mavlink(self, message):
The function can send arbitrary messages/commands to a vehicle at any time and in any vehicle mode. It is particularly useful for
controlling vehicles outside of missions (for example, in GUIDED mode).

The :py:func:`message_factory <droneapi.lib.Vehicle.message_factory>` is used to create messages in the appropriate format.
The :py:func:`message_factory <droneapi.lib.Vehicle.message_factory>` is used to create messages in the appropriate format.
Callers do not need to populate sysId/componentId/crc in the packet as the method will take care of that before sending.

:param: message: A ``MAVLink_message`` instance, created using :py:func:`message_factory <droneapi.lib.Vehicle.message_factory>`.
Expand All @@ -677,7 +677,7 @@ def set_mavlink_callback(self, callback):

The code snippet below shows how to set a "demo" callback function as the callback handler:

.. code:: python
.. code:: python

# Demo callback handler for raw MAVLink messages
def mavrx_debug_handler(message):
Expand Down Expand Up @@ -754,12 +754,12 @@ class Parameters(HasObservers):
vehicle.parameters['THR_MIN']=100
vehicle.flush()

.. note::
.. note::

At time of writing ``Parameters`` does not implement the observer methods, and change notification for parameters
is not supported.

.. todo::
.. todo::

Check to see if observers have been implemented and if so, update the information here, in about, and in Vehicle class:
https://github.com/diydrones/dronekit-python/issues/107
Expand All @@ -780,9 +780,9 @@ class Command(mavutil.mavlink.MAVLink_mission_item_message):
mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, 0, 0, 0, 0, 0,-34.364114, 149.166022, 30)


:param target_system: The id number of the message's target system (drone, GSC) within the MAVLink network.
Set this to zero (broadcast) when communicating with a companion computer.
:param target_component: The id of a component the message should be routed to within the target system
:param target_system: The id number of the message's target system (drone, GSC) within the MAVLink network.
Set this to zero (broadcast) when communicating with a companion computer.
:param target_component: The id of a component the message should be routed to within the target system
(for example, the camera). Set to zero (broadcast) in most cases.
:param seq: The sequence number within the mission (the autopilot will reject messages sent out of sequence).
This should be set to zero as the API will automatically set the correct value when uploading a mission.
Expand Down Expand Up @@ -845,8 +845,7 @@ class CommandSequence(object):
0, 0, 0, 0, 0, 0,
lat, lon, altitude)
cmds.add(cmd)
vehicle.flush()

vehicle.flush()

.. py:function:: takeoff(altitude)

Expand All @@ -871,18 +870,18 @@ class CommandSequence(object):

def download(self):
'''
Download all waypoints from the vehicle.
Download all waypoints from the vehicle.

The download is asynchronous. Use :py:func:`wait_valid()` to block your thread until the download is complete.
'''
The download is asynchronous. Use :py:func:`wait_valid()` to block your thread until the download is complete.
'''
pass

def wait_valid(self):
'''
Block the calling thread until waypoints have been downloaded.
Block the calling thread until waypoints have been downloaded.

This can be called after :py:func:`download()` to block the thread until the asynchronous download is complete.
'''
This can be called after :py:func:`download()` to block the thread until the asynchronous download is complete.
'''
pass


Expand Down Expand Up @@ -921,10 +920,10 @@ def add(self, cmd):
@property
def count(self):
'''
Return number of waypoints.
Return number of waypoints.

:return: The number of waypoints in the sequence.
'''
:return: The number of waypoints in the sequence.
'''
return 0

@property
Expand Down
7 changes: 4 additions & 3 deletions examples/vehicle_state/vehicle_state.py
Original file line number Diff line number Diff line change
Expand Up @@ -22,9 +22,10 @@
print " Attitude: %s" % v.attitude
print " Velocity: %s" % v.velocity
print " GPS: %s" % v.gps_0
print " groundspeed: %s" % v.groundspeed
print " airspeed: %s" % v.airspeed
print " mount_status: %s" % v.mount_status
print " Groundspeed: %s" % v.groundspeed
print " Airspeed: %s" % v.airspeed
print " Mount status: %s" % v.mount_status
print " Battery: %s" % v.battery
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

When this gets printed it prints "Battery: Battery: ..."

print " Mode: %s" % v.mode.name # settable
print " Armed: %s" % v.armed # settable

Expand Down