From 371d62f703485e31fa5eb80faefcc0f83281de86 Mon Sep 17 00:00:00 2001 From: mhefny Date: Thu, 29 Jun 2017 06:34:18 +0200 Subject: [PATCH 1/8] fixing altitude float --- dronekit/__init__.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/dronekit/__init__.py b/dronekit/__init__.py index 68cf82c54..d962956d7 100644 --- a/dronekit/__init__.py +++ b/dronekit/__init__.py @@ -1983,7 +1983,7 @@ def simple_takeoff(self, alt=None): """ if alt is not None: altitude = float(alt) - if math.isnan(alt) or math.isinf(alt): + if math.isnan(altitude) or math.isinf(altitude): raise ValueError("Altitude was NaN or Infinity. Please provide a real number") self._master.mav.command_long_send(0, 0, mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 0, 0, 0, 0, 0, altitude) From 53970d853cbbe20c94f5b68285325d588f9d8a4b Mon Sep 17 00:00:00 2001 From: MHefny Date: Tue, 1 Aug 2017 05:08:29 +0200 Subject: [PATCH 2/8] added isflying --- .vscode/settings.json | 3 +++ dronekit/__init__.py | 13 +++++++++++++ 2 files changed, 16 insertions(+) create mode 100644 .vscode/settings.json diff --git a/.vscode/settings.json b/.vscode/settings.json new file mode 100644 index 000000000..fe7159848 --- /dev/null +++ b/.vscode/settings.json @@ -0,0 +1,3 @@ +{ + "python.linting.pylintEnabled": false +} \ No newline at end of file diff --git a/dronekit/__init__.py b/dronekit/__init__.py index 51c659ec4..fe5a875f5 100644 --- a/dronekit/__init__.py +++ b/dronekit/__init__.py @@ -1067,6 +1067,7 @@ def listener(self, name, m): self._heading = None self._airspeed = None self._groundspeed = None + self._isflying = False @self.on_message('VFR_HUD') def listener(self, name, m): @@ -1790,6 +1791,18 @@ def system_status(self): 7: SystemStatus('POWEROFF'), }.get(self._system_status, None) + + @property + def isflying (self): + isFlying = ((self._system_status == MyVehicle.MAV_STATE_ACTIVE) or + ((self._isflying == True) and (self._system_status == MyVehicle.MAV_STATE_CRITICAL or self._system_status == MyVehicle.MAV_STATE_EMERGENCY))) + + self._isflying = isFlying + + return self._isflying + + + @property def heading(self): """ From 28741d9ec23127480ca73d212c09b9c1cfc109c3 Mon Sep 17 00:00:00 2001 From: MHefny Date: Tue, 1 Aug 2017 05:11:36 +0200 Subject: [PATCH 3/8] isFlying --- .vscode/settings.json | 3 --- 1 file changed, 3 deletions(-) diff --git a/.vscode/settings.json b/.vscode/settings.json index fe7159848..e69de29bb 100644 --- a/.vscode/settings.json +++ b/.vscode/settings.json @@ -1,3 +0,0 @@ -{ - "python.linting.pylintEnabled": false -} \ No newline at end of file From 1348010fe5598c1d56297eb20d8a0ee7159a4dbc Mon Sep 17 00:00:00 2001 From: MHefny Date: Tue, 1 Aug 2017 17:45:59 +0200 Subject: [PATCH 4/8] fix missing constants --- dronekit/__init__.py | 14 ++++++++++++-- examples/vehicle_state/vehicle_state.py | 4 +++- 2 files changed, 15 insertions(+), 3 deletions(-) diff --git a/dronekit/__init__.py b/dronekit/__init__.py index fe5a875f5..76bc70e33 100644 --- a/dronekit/__init__.py +++ b/dronekit/__init__.py @@ -1013,6 +1013,16 @@ class Vehicle(HasObservers): to the project! """ + MAV_STATE_UNINIT = 0 + MAV_STATE_BOOT = 1 + MAV_STATE_CALIBRATING = 2 + MAV_STATE_STANDBY = 3 + MAV_STATE_ACTIVE = 4 + MAV_STATE_CRITICAL = 5 + MAV_STATE_EMERGENCY = 6 + MAV_STATE_HILSIM = 7 + MAV_STATE_POWEROFF = 8 + def __init__(self, handler): super(Vehicle, self).__init__() @@ -1794,8 +1804,8 @@ def system_status(self): @property def isflying (self): - isFlying = ((self._system_status == MyVehicle.MAV_STATE_ACTIVE) or - ((self._isflying == True) and (self._system_status == MyVehicle.MAV_STATE_CRITICAL or self._system_status == MyVehicle.MAV_STATE_EMERGENCY))) + isFlying = ((self._system_status == Vehicle.MAV_STATE_ACTIVE) or + ((self._isflying == True) and (self._system_status == Vehicle.MAV_STATE_CRITICAL or Vehicle._system_status == self.MAV_STATE_EMERGENCY))) self._isflying = isFlying diff --git a/examples/vehicle_state/vehicle_state.py b/examples/vehicle_state/vehicle_state.py index c4d7d55c6..1829019aa 100644 --- a/examples/vehicle_state/vehicle_state.py +++ b/examples/vehicle_state/vehicle_state.py @@ -10,7 +10,7 @@ Full documentation is provided at http://python.dronekit.io/examples/vehicle_state.html """ -from dronekit import connect, VehicleMode +import connect, VehicleMode import time #Set up option parsing to get connection string @@ -77,6 +77,7 @@ print " Rangefinder voltage: %s" % vehicle.rangefinder.voltage print " Heading: %s" % vehicle.heading print " Is Armable?: %s" % vehicle.is_armable +print " IsFlying: %s" % vehicle.isflying print " System status: %s" % vehicle.system_status.state print " Groundspeed: %s" % vehicle.groundspeed # settable print " Airspeed: %s" % vehicle.airspeed # settable @@ -85,6 +86,7 @@ + # Get Vehicle Home location - will be `None` until first set by autopilot while not vehicle.home_location: cmds = vehicle.commands From 2b1c5a78efce217065d5578b2fdb31effff4f68c Mon Sep 17 00:00:00 2001 From: MHefny Date: Tue, 1 Aug 2017 17:50:53 +0200 Subject: [PATCH 5/8] fixes --- examples/vehicle_state/vehicle_state.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/vehicle_state/vehicle_state.py b/examples/vehicle_state/vehicle_state.py index 1829019aa..e0f9863ca 100644 --- a/examples/vehicle_state/vehicle_state.py +++ b/examples/vehicle_state/vehicle_state.py @@ -10,7 +10,7 @@ Full documentation is provided at http://python.dronekit.io/examples/vehicle_state.html """ -import connect, VehicleMode +from dronekit import connect, VehicleMode import time #Set up option parsing to get connection string From 4289a84204fd6da484ffed8767287da5038fbf50 Mon Sep 17 00:00:00 2001 From: MHefny Date: Tue, 1 Aug 2017 17:52:14 +0200 Subject: [PATCH 6/8] fix --- examples/vehicle_state/vehicle_state.py | 1 - 1 file changed, 1 deletion(-) diff --git a/examples/vehicle_state/vehicle_state.py b/examples/vehicle_state/vehicle_state.py index e0f9863ca..96520ca43 100644 --- a/examples/vehicle_state/vehicle_state.py +++ b/examples/vehicle_state/vehicle_state.py @@ -86,7 +86,6 @@ - # Get Vehicle Home location - will be `None` until first set by autopilot while not vehicle.home_location: cmds = vehicle.commands From d4b5b00e747bf108688b015ab1e0b0bb9bac8646 Mon Sep 17 00:00:00 2001 From: MHefny Date: Tue, 1 Aug 2017 18:01:44 +0200 Subject: [PATCH 7/8] update example --- examples/vehicle_state/vehicle_state.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/examples/vehicle_state/vehicle_state.py b/examples/vehicle_state/vehicle_state.py index 96520ca43..8dd9f0f52 100644 --- a/examples/vehicle_state/vehicle_state.py +++ b/examples/vehicle_state/vehicle_state.py @@ -34,7 +34,7 @@ # Connect to the Vehicle. # Set `wait_ready=True` to ensure default attributes are populated before `connect()` returns. print "\nConnecting to vehicle on: %s" % connection_string -vehicle = connect(connection_string, wait_ready=True) +vehicle = connect(connection_string, wait_ready=False) vehicle.wait_ready('autopilot_version') @@ -77,7 +77,7 @@ print " Rangefinder voltage: %s" % vehicle.rangefinder.voltage print " Heading: %s" % vehicle.heading print " Is Armable?: %s" % vehicle.is_armable -print " IsFlying: %s" % vehicle.isflying +print " Is Flying: %s" % vehicle.isflying print " System status: %s" % vehicle.system_status.state print " Groundspeed: %s" % vehicle.groundspeed # settable print " Airspeed: %s" % vehicle.airspeed # settable From 0d2ddd444bd83e7ea2ac3515c50228aa60ae5f12 Mon Sep 17 00:00:00 2001 From: MHefny Date: Tue, 1 Aug 2017 18:06:55 +0200 Subject: [PATCH 8/8] fix example --- examples/vehicle_state/vehicle_state.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/vehicle_state/vehicle_state.py b/examples/vehicle_state/vehicle_state.py index 8dd9f0f52..3fea45161 100644 --- a/examples/vehicle_state/vehicle_state.py +++ b/examples/vehicle_state/vehicle_state.py @@ -34,7 +34,7 @@ # Connect to the Vehicle. # Set `wait_ready=True` to ensure default attributes are populated before `connect()` returns. print "\nConnecting to vehicle on: %s" % connection_string -vehicle = connect(connection_string, wait_ready=False) +vehicle = connect(connection_string, wait_ready=True) vehicle.wait_ready('autopilot_version')