From a2abe638f93dc72bdd06c218d8cb1deab9d73edc Mon Sep 17 00:00:00 2001 From: TongBingda <33590905+TongBingda@users.noreply.github.com> Date: Wed, 12 Jul 2023 21:24:01 +0800 Subject: [PATCH 1/3] Update __init__.py The RAW values of the servo outputs. An object of this type is returned by :py:attr:`Vehicle.servos`. :param port: Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX. :param servo_raw['1'] ~ servo_raw['16']: Servo output 1 ~ 16 value. --- dronekit/__init__.py | 40 ++++++++++++++++++++++++++++++++++++++++ 1 file changed, 40 insertions(+) diff --git a/dronekit/__init__.py b/dronekit/__init__.py index bc05a7098..16c9b6b03 100644 --- a/dronekit/__init__.py +++ b/dronekit/__init__.py @@ -247,6 +247,23 @@ def __str__(self): return "Wind: wind direction: {}, wind speed: {}, wind speed z: {}".format(self.wind_direction, self.wind_speed, self.wind_speed_z) +class Servos(object): + """ + The RAW values of the servo outputs. + + An object of this type is returned by :py:attr:`Vehicle.servos`. + + :param port: Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX. + :param servo_raw['1'] ~ servo_raw['16']: Servo output 1 ~ 16 value. + """ + def __init__(self, port, servo_raw): + self.port = port + self.servo_raw = servo_raw + + def __str__(self): + return "Servos: servo output port: {}, servo value: {}".format(self.port, self.servo_raw) + + class Battery(object): """ System battery information. @@ -1195,6 +1212,20 @@ def set_rc(chnum, v): self.notify_attribute_listeners('channels', self.channels) + self._port = None + self._servo_raw = None + + @self.on_message('SERVO_OUTPUT_RAW') + def listener(self, name, m): + def set_servo(servonum, v): + """Private utility for handling servo output messages""" + self._servo_raw[str(i)] = v + self._port = m.port + self._servo_raw = {} + for i in range(1, 16+1): + set_servo(i, getattr(m, "servo{}_raw".format(i))) + self.notify_attribute_listeners('servos', self.servos) + self._voltage = None self._current = None self._level = None @@ -1727,6 +1758,15 @@ def wind(self): return None return Wind(self._wind_direction, self._wind_speed, self._wind_speed_z) + @property + def servos(self): + """ + Current servo outputs (:py:class:`Servos`) + """ + if self._port is None or self._servo_raw is None: + return None + return Servos(self._port, self._servo_raw) + @property def battery(self): """ From f635f376abd196f6d8a7c17744eae0b896e041b1 Mon Sep 17 00:00:00 2001 From: TongBingda <33590905+TongBingda@users.noreply.github.com> Date: Wed, 12 Jul 2023 21:26:29 +0800 Subject: [PATCH 2/3] Update __init__.py spelling mistake correction --- dronekit/__init__.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/dronekit/__init__.py b/dronekit/__init__.py index 16c9b6b03..9e883857a 100644 --- a/dronekit/__init__.py +++ b/dronekit/__init__.py @@ -1752,7 +1752,7 @@ def listener(self, attr_name, value): @property def wind(self): """ - Current wind status (:pu:class: `Wind`) + Current wind status (:py:class: `Wind`) """ if self._wind_direction is None or self._wind_speed is None or self._wind_speed_z is None: return None From 4082b131d9247abe2e1652dd3a717ff66711ad87 Mon Sep 17 00:00:00 2001 From: TongBingda <33590905+TongBingda@users.noreply.github.com> Date: Wed, 19 Jul 2023 22:03:54 +0800 Subject: [PATCH 3/3] Update SERVO_OUTPUT_RAW message for mavlink 1 and 2 When running ardupilot firmware using the sitl method, SERVO_OUTPUT_RAW usually uses mavlink 2.0, whereas this message usually uses mavlink 1.0 when I run ardupilot firmware using the Cube Orange, which makes it impossible to get the values from servo9_raw to servo16 _raw values. So I used len(m.lengths) to get the actual number of servo_outputs. --- dronekit/__init__.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/dronekit/__init__.py b/dronekit/__init__.py index 9e883857a..42ee0d8da 100644 --- a/dronekit/__init__.py +++ b/dronekit/__init__.py @@ -1222,7 +1222,7 @@ def set_servo(servonum, v): self._servo_raw[str(i)] = v self._port = m.port self._servo_raw = {} - for i in range(1, 16+1): + for i in range(1, len(m.lengths)-1): set_servo(i, getattr(m, "servo{}_raw".format(i))) self.notify_attribute_listeners('servos', self.servos)