Skip to content

Commit d425e24

Browse files
committed
Added Rangefinder class
1 parent 9ed904f commit d425e24

File tree

2 files changed

+57
-32
lines changed

2 files changed

+57
-32
lines changed

droneapi/lib/__init__.py

Lines changed: 44 additions & 31 deletions
Original file line numberDiff line numberDiff line change
@@ -192,9 +192,24 @@ def __str__(self):
192192
return "Battery:voltage={},current={},level={}".format(self.voltage, self.current, self.level)
193193

194194

195+
class Rangefinder(object):
196+
"""
197+
Rangefinder readings.
198+
199+
:param distance: Distance.
200+
:param voltage: Voltage.
201+
"""
202+
def __init__(self, distance, voltage):
203+
self.distance = distance
204+
self.voltage = voltage
205+
206+
def __str__(self):
207+
return "Rangefinder: distance={}, voltage={}".format(self.distance, self.voltage)
208+
209+
195210
class VehicleMode(object):
196211
"""
197-
This object is used to get and set the current "flight mode".
212+
This object is used to get and set the current "flight mode".
198213
199214
The flight mode determines the behaviour of the vehicle and what commands it can obey.
200215
The recommended flight modes for *DroneKit-Python* apps depend on the vehicle type:
@@ -330,7 +345,7 @@ def location_callback(location):
330345
:param attr_name: The attribute to watch.
331346
:param observer: The callback to invoke when a change in the attribute is detected.
332347
333-
.. todo:: Check that the defect for endless repetition after thread closes is fixed: https://github.com/diydrones/dronekit-python/issues/74
348+
.. todo:: Check that the defect for endless repetition after thread closes is fixed: https://github.com/diydrones/dronekit-python/issues/74
334349
"""
335350
l = self.__observers.get(attr_name)
336351
if l is None:
@@ -456,7 +471,7 @@ class Vehicle(HasObservers):
456471
457472
.. py:attribute:: mount_status
458473
459-
Current status of the camera mount (gimbal) as a three element list: ``[ pitch, yaw, roll ]``.
474+
Current status of the camera mount (gimbal) as a three element list: ``[ pitch, yaw, roll ]``.
460475
461476
The values in the list are set to ``None`` if no mount is configured.
462477
@@ -465,13 +480,13 @@ class Vehicle(HasObservers):
465480
466481
Current system :py:class:`Battery` status.
467482
468-
483+
469484
.. py:attribute:: channel_override
470485
471486
.. warning::
472487
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!
488+
RC override may be useful for simulating user input and when implementing certain types of joystick control.
489+
It should not be used for direct control of vehicle channels unless there is no other choice!
475490
476491
Instead use the appropriate MAVLink commands like DO_SET_SERVO/DO_SET_RELAY, or more generally
477492
set the desired position or direction/speed.
@@ -481,15 +496,15 @@ class Vehicle(HasObservers):
481496
482497
To cancel an override call ``channel_override`` again, setting zero for the overridden channels.
483498
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>`_ ,
499+
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:
500+
`Plane <http://plane.ardupilot.com/wiki/arduplane-parameters/#rcmap__parameters>`_,
501+
`Copter <http://copter.ardupilot.com/wiki/configuration/arducopter-parameters/#rcmap__parameters>`_ ,
487502
`Rover <http://rover.ardupilot.com/wiki/apmrover2-parameters/#rcmap__parameters>`_).
488503
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
504+
The remaining channel values are configurable, and their purpose can be determined using the
505+
`RCn_FUNCTION parameters <http://plane.ardupilot.com/wiki/flight-features/channel-output-functions/>`_.
506+
In general a value of 0 set for a specific ``RCn_FUNCTION`` indicates that the channel can be
507+
`mission controlled <http://plane.ardupilot.com/wiki/flight-features/channel-output-functions/#disabled>`_ (i.e. it will not directly be
493508
controlled by normal autopilot code).
494509
495510
An example of setting and clearing the override is given below:
@@ -514,8 +529,8 @@ class Vehicle(HasObservers):
514529
515530
https://github.com/diydrones/dronekit-python/issues/72
516531
517-
.. todo::
518-
532+
.. todo::
533+
519534
channel_override/channel_readback documentation
520535
521536
In a future update strings will be defined per vehicle type ('pitch', 'yaw', 'roll' etc...)
@@ -572,9 +587,9 @@ def commands(self):
572587
"""
573588
Gets the editable waypoints for this vehicle (the current "mission").
574589
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-
590+
This can be used to get, create, and modify a mission. It can also be used for direct control of vehicle position
591+
(outside missions) using the :py:func:`goto <droneapi.lib.CommandSequence.goto>` method.
592+
578593
:returns: A :py:class:`CommandSequence` containing the waypoints for this vehicle.
579594
"""
580595
None
@@ -603,9 +618,9 @@ def get_mission(self, query_params):
603618
604619
Returns an object providing access to historical missions.
605620
606-
.. warning::
621+
.. warning::
607622
608-
Mission objects are only accessible from the REST API in release 1 (most use-cases requiring missions prefer a
623+
Mission objects are only accessible from the REST API in release 1 (most use-cases requiring missions prefer a
609624
610625
:param query_params: Some set of arguments that can be used to find a past mission
611626
:return: Mission - the mission object.
@@ -639,7 +654,7 @@ def message_factory(self):
639654
msg = vehicle.message_factory.image_trigger_control_encode(True)
640655
vehicle.send_mavlink(msg)
641656
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
657+
There is no need to specify the system id, component id or sequence number of messages (if defined in the message type) as the
643658
API will set these appropriately when the message is sent.
644659
645660
.. todo:: When I have a custom message guide topic. Link from here to it.
@@ -655,7 +670,7 @@ def send_mavlink(self, message):
655670
The function can send arbitrary messages/commands to a vehicle at any time and in any vehicle mode. It is particularly useful for
656671
controlling vehicles outside of missions (for example, in GUIDED mode).
657672
658-
The :py:func:`message_factory <droneapi.lib.Vehicle.message_factory>` is used to create messages in the appropriate format.
673+
The :py:func:`message_factory <droneapi.lib.Vehicle.message_factory>` is used to create messages in the appropriate format.
659674
Callers do not need to populate sysId/componentId/crc in the packet as the method will take care of that before sending.
660675
661676
:param: message: A ``MAVLink_message`` instance, created using :py:func:`message_factory <droneapi.lib.Vehicle.message_factory>`.
@@ -677,7 +692,7 @@ def set_mavlink_callback(self, callback):
677692
678693
The code snippet below shows how to set a "demo" callback function as the callback handler:
679694
680-
.. code:: python
695+
.. code:: python
681696
682697
# Demo callback handler for raw MAVLink messages
683698
def mavrx_debug_handler(message):
@@ -754,12 +769,12 @@ class Parameters(HasObservers):
754769
vehicle.parameters['THR_MIN']=100
755770
vehicle.flush()
756771
757-
.. note::
772+
.. note::
758773
759774
At time of writing ``Parameters`` does not implement the observer methods, and change notification for parameters
760775
is not supported.
761776
762-
.. todo::
777+
.. todo::
763778
764779
Check to see if observers have been implemented and if so, update the information here, in about, and in Vehicle class:
765780
https://github.com/diydrones/dronekit-python/issues/107
@@ -780,9 +795,9 @@ class Command(mavutil.mavlink.MAVLink_mission_item_message):
780795
mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, 0, 0, 0, 0, 0,-34.364114, 149.166022, 30)
781796
782797
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
798+
:param target_system: The id number of the message's target system (drone, GSC) within the MAVLink network.
799+
Set this to zero (broadcast) when communicating with a companion computer.
800+
:param target_component: The id of a component the message should be routed to within the target system
786801
(for example, the camera). Set to zero (broadcast) in most cases.
787802
:param seq: The sequence number within the mission (the autopilot will reject messages sent out of sequence).
788803
This should be set to zero as the API will automatically set the correct value when uploading a mission.
@@ -845,7 +860,7 @@ class CommandSequence(object):
845860
0, 0, 0, 0, 0, 0,
846861
lat, lon, altitude)
847862
cmds.add(cmd)
848-
vehicle.flush()
863+
vehicle.flush()
849864
850865
.. py:function:: takeoff(altitude)
851866
@@ -943,5 +958,3 @@ def next(self, value):
943958
.. INTERNAL NOTE: (implementation provided by subclass)
944959
"""
945960
pass
946-
947-

droneapi/module/api.py

Lines changed: 13 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -7,7 +7,8 @@
77
from MAVProxy.modules.lib import mp_module
88
from droneapi.lib.WebClient import *
99
from droneapi.lib import APIConnection, Vehicle, VehicleMode, Location, \
10-
Attitude, GPSInfo, Parameters, CommandSequence, APIException, Battery
10+
Attitude, GPSInfo, Parameters, CommandSequence, APIException, Battery, \
11+
Rangefinder
1112

1213
# Enable logging here (until this code can be moved into mavproxy)
1314
logging.basicConfig(level=logging.DEBUG)
@@ -178,6 +179,10 @@ def location(self):
178179
def battery(self):
179180
return Battery(self.__module.voltage, self.__module.current, self.__module.level)
180181

182+
@property
183+
def rangefinder(self):
184+
return Rangefinder(self.__module.rngfnd_distance, self.__module.rngfnd_voltage)
185+
181186
@property
182187
def velocity(self):
183188
return [ self.__module.vx, self.__module.vy, self.__module.vz ]
@@ -382,6 +387,9 @@ def __init__(self, mpstate):
382387
self.satellites_visible = None
383388
self.fix_type = None # FIXME support multiple GPSs per vehicle - possibly by using componentId
384389

390+
self.rngfnd_distance = None
391+
self.rngfnd_voltage = None
392+
385393
self.next_thread_num = 0 # Monotonically increasing
386394
self.threads = {} # A map from int ID to thread object
387395

@@ -472,6 +480,10 @@ def set(chnum, v):
472480
self.mount_roll = m.pointing_b / 100
473481
self.mount_yaw = m.pointing_c / 100
474482
self.__on_change('mount')
483+
elif typ == "RANGEFINDER":
484+
self.rngfnd_distance = m.distance
485+
self.rngfnd_voltage = m.voltage
486+
self.__on_change('rangefinder')
475487

476488

477489
if (self.vehicle is not None) and hasattr(self.vehicle, 'mavrx_callback'):

0 commit comments

Comments
 (0)