From 30d5f455471b934c487ab79a173ec1c7e6e07686 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 14 Mar 2019 16:58:50 +1100 Subject: [PATCH 1/6] Release 2.9.2 notes and version bump --- CHANGELOG.md | 26 ++++++++++++++++++++++++++ setup.py | 2 +- 2 files changed, 27 insertions(+), 1 deletion(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 21331ab2e..8949fec49 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,5 +1,31 @@ # Changelog + +## Version 2.9.2 (2019-03-14) + +### Improvements +* CI integration improvements +* Python3 compatability +* use logging module +* log statustexts +* documentation improvements +* convenience functions added: wait_for, wait_for_armable, arm, disarm, wait_for_mode, wait_for_alt, wait_simple_takeoff +* play_tune method added +* reboot method added +* send_calibrate_gyro, send_calibrate_magnetometer, send_calibrate_magnetometer, send_calibrate_vehicle_level, send_calibrate_barometer all added +* update gimbal orientation from MOUNT_ORIENTATION +* add a still-waiting callback for connect() to provide debug on where the connection is up to +* several new tests added (including, play_tune, reboot and set_attitude_target) + +### Cleanup +* flake8 compliance improvements +* test includes pruned +* examples cleaned up + +### Bug Fixes +* ignore GCS heartbeats for the purposes of link up +* many! + ## Version 2.9.1 (2017-04-21) ### Improvements diff --git a/setup.py b/setup.py index cc24953f8..2dad0f18b 100644 --- a/setup.py +++ b/setup.py @@ -1,6 +1,6 @@ import setuptools -version = '2.9.1' +version = '2.9.2' setuptools.setup( name='dronekit', From d798accc4a98ac0593f910202a68b02db7c5f16a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Dawid=20Kope=C4=87?= Date: Fri, 8 Jul 2022 13:17:21 +0200 Subject: [PATCH 2/6] Bugfix - sometimes removing already gotten parameters from params_set --- dronekit/__init__.py | 13 +++++++++---- 1 file changed, 9 insertions(+), 4 deletions(-) diff --git a/dronekit/__init__.py b/dronekit/__init__.py index b6ff96227..2cb964cf0 100644 --- a/dronekit/__init__.py +++ b/dronekit/__init__.py @@ -1320,13 +1320,18 @@ def listener(_): @self.on_message(['PARAM_VALUE']) def listener(self, name, msg): - # If we discover a new param count, assume we - # are receiving a new param set. + # If we discover a new params count, + # we are modify length of params set if self._params_count != msg.param_count: self._params_loaded = False self._params_start = True self._params_count = msg.param_count - self._params_set = [None] * msg.param_count + + diff = self._params_count - len(self._params_set) + if diff > 0: + self._params_set += [None] * diff + else: + self._params_set[:diff] # Attempt to set the params. We throw an error # if the index is out of range of the count or @@ -2544,7 +2549,7 @@ def listener(vehicle, name, m): @vehicle.on_message('MOUNT_ORIENTATION') def listener(vehicle, name, m): - self._pitch = m.pitch + self._pitch = m.pitch self._roll = m.roll self._yaw = m.yaw vehicle.notify_attribute_listeners('gimbal', vehicle.gimbal) From de0676504beb6751095433c9dbe904afaa6eb7d0 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Dawid=20Kope=C4=87?= Date: Wed, 8 Mar 2023 13:19:27 +0100 Subject: [PATCH 3/6] change length of params_set in params loader listener --- dronekit/__init__.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/dronekit/__init__.py b/dronekit/__init__.py index 73269c38f..7bf9490eb 100644 --- a/dronekit/__init__.py +++ b/dronekit/__init__.py @@ -1366,8 +1366,8 @@ def listener(self, name, msg): diff = self._params_count - len(self._params_set) if diff > 0: self._params_set += [None] * diff - else: - self._params_set[:diff] + elif diff < 0: + self._params_set = self._params_set[:self._params_count] # Attempt to set the params. We throw an error # if the index is out of range of the count or From 0d12795f81b39094b9a0d8d5010775d07e60b7a1 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Dawid=20Kope=C4=87?= Date: Wed, 8 Mar 2023 13:36:21 +0100 Subject: [PATCH 4/6] LongDescription --- setup.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/setup.py b/setup.py index 233c7b5d8..49d7477e2 100644 --- a/setup.py +++ b/setup.py @@ -3,6 +3,9 @@ version = '2.9.2' +with open(os.path.join(os.path.dirname(__file__), 'README.md')) as f: + LongDescription = f.read() + setuptools.setup( name='dronekit', zip_safe=True, From 2f3f7b006f24e3c1f56926b6bc6a0083cd2c14ca Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Dawid=20Kope=C4=87?= Date: Wed, 8 Mar 2023 16:23:58 +0100 Subject: [PATCH 5/6] add comments and debug message --- dronekit/__init__.py | 14 +++++++++++++- 1 file changed, 13 insertions(+), 1 deletion(-) diff --git a/dronekit/__init__.py b/dronekit/__init__.py index 7bf9490eb..0b68f57e2 100644 --- a/dronekit/__init__.py +++ b/dronekit/__init__.py @@ -242,7 +242,7 @@ def __init__(self, wind_direction, wind_speed, wind_speed_z): self.wind_direction = wind_direction self.wind_speed = wind_speed self.wind_speed_z = wind_speed_z - + def __str__(self): return "Wind: wind direction: {}, wind speed: {}, wind speed z: {}".format(self.wind_direction, self.wind_speed, self.wind_speed_z) @@ -1380,6 +1380,11 @@ def listener(self, name, msg): self._params_set[msg.param_index] = msg self._params_map[msg.param_id] = msg.param_value + print( + 'msg.param_id: {} msg.param_index: {} msg.param_count: {} len(self._params_map): {}'.format( + msg.param_id, msg.param_index, msg.param_count, len(self._params_map) + ) + ) self._parameters.notify_attribute_listeners(msg.param_id, msg.param_value, cache=True) except: @@ -2341,13 +2346,20 @@ def initialize(self, rate=4, heartbeat_timeout=30): self.add_message_listener('HEARTBEAT', self.send_capabilities_request) # Ensure initial parameter download has started. + # TODO change to this when still trouble with infinity loop read params + # cnt = 50 + # while cnt: while True: # This fn actually rate limits itself to every 2s. # Just retry with persistence to get our first param stream. self._master.param_fetch_all() + # TODO change to this when still trouble with full load params + # self._master.param_fetch_one(0) time.sleep(0.1) if self._params_count > -1: break + # TODO change to this when still trouble with infinity loop read params + # cnt -= 1 def send_capabilties_request(self, vehicle, name, m): '''An alias for send_capabilities_request. From 686a34262310688a3bf116f2df57e47e8c7bf495 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Dawid=20Kope=C4=87?= Date: Tue, 22 Aug 2023 12:56:55 +0200 Subject: [PATCH 6/6] auto update test --- dronekit/__init__.py | 11 ++--------- 1 file changed, 2 insertions(+), 9 deletions(-) diff --git a/dronekit/__init__.py b/dronekit/__init__.py index 0b68f57e2..c7c0b90f0 100644 --- a/dronekit/__init__.py +++ b/dronekit/__init__.py @@ -1380,13 +1380,7 @@ def listener(self, name, msg): self._params_set[msg.param_index] = msg self._params_map[msg.param_id] = msg.param_value - print( - 'msg.param_id: {} msg.param_index: {} msg.param_count: {} len(self._params_map): {}'.format( - msg.param_id, msg.param_index, msg.param_count, len(self._params_map) - ) - ) - self._parameters.notify_attribute_listeners(msg.param_id, msg.param_value, - cache=True) + self._parameters.notify_attribute_listeners(msg.param_id, msg.param_value, cache=True) except: import traceback traceback.print_exc() @@ -2340,8 +2334,7 @@ def initialize(self, rate=4, heartbeat_timeout=30): # Initialize data stream. if rate is not None: - self._master.mav.request_data_stream_send(0, 0, mavutil.mavlink.MAV_DATA_STREAM_ALL, - rate, 1) + self._master.mav.request_data_stream_send(0, 0, mavutil.mavlink.MAV_DATA_STREAM_ALL, rate, 1) self.add_message_listener('HEARTBEAT', self.send_capabilities_request)