From ae487b8d71cd1d5a6b923bc40d5af4ab5c0b3653 Mon Sep 17 00:00:00 2001 From: Chris Heintz Date: Mon, 24 Jul 2017 12:29:41 -0400 Subject: [PATCH 1/2] First attempt at attitude rate properties --- dronekit/__init__.py | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/dronekit/__init__.py b/dronekit/__init__.py index 51c659ec4..e6eba08a7 100644 --- a/dronekit/__init__.py +++ b/dronekit/__init__.py @@ -85,10 +85,13 @@ class Attitude(object): :param roll: Roll in radians """ - def __init__(self, pitch, yaw, roll): + def __init__(self, pitch, yaw, roll,pitchspeed,yawspeed,rollspeed): self.pitch = pitch self.yaw = yaw self.roll = roll + self.pitchspeed = pitchspeed + self.yawspeed = yawspeed + self.rollspeed = rollspeed def __str__(self): fmt = '{}:pitch={pitch},yaw={yaw},roll={roll}' @@ -1712,7 +1715,7 @@ def attitude(self): """ Current vehicle attitude - pitch, yaw, roll (:py:class:`Attitude`). """ - return Attitude(self._pitch, self._yaw, self._roll) + return Attitude(self._pitch, self._yaw, self._roll,self._pitchspeed,self._yawspeed,self._rollspeed) @property def gps_0(self): From 7b6bb38c4f47f47e1b83970d2cc537ed16976d68 Mon Sep 17 00:00:00 2001 From: Chris Heintz Date: Mon, 24 Jul 2017 13:18:05 -0400 Subject: [PATCH 2/2] Fix whitespace --- dronekit/__init__.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/dronekit/__init__.py b/dronekit/__init__.py index e6eba08a7..468d045c7 100644 --- a/dronekit/__init__.py +++ b/dronekit/__init__.py @@ -89,9 +89,9 @@ def __init__(self, pitch, yaw, roll,pitchspeed,yawspeed,rollspeed): self.pitch = pitch self.yaw = yaw self.roll = roll - self.pitchspeed = pitchspeed - self.yawspeed = yawspeed - self.rollspeed = rollspeed + self.pitchspeed = pitchspeed + self.yawspeed = yawspeed + self.rollspeed = rollspeed def __str__(self): fmt = '{}:pitch={pitch},yaw={yaw},roll={roll}'