Skip to content

Commit 6eaa942

Browse files
pietrodnpeterbarker
authored andcommitted
Faster comparisons with None/True/False, various performance fixes
1 parent 513ab4e commit 6eaa942

File tree

1 file changed

+13
-13
lines changed

1 file changed

+13
-13
lines changed

dronekit/__init__.py

Lines changed: 13 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -304,7 +304,7 @@ def __init__(self, raw_version, autopilot_type, vehicle_type):
304304
self.autopilot_type = autopilot_type
305305
self.vehicle_type = vehicle_type
306306
self.raw_version = raw_version
307-
if(raw_version == None):
307+
if raw_version is None:
308308
self.major = None
309309
self.minor = None
310310
self.patch = None
@@ -640,7 +640,7 @@ def notify_attribute_listeners(self, attr_name, value, cache=False):
640640
"""
641641
# Cached values are not re-sent if they are unchanged.
642642
if cache:
643-
if attr_name in self._attribute_cache and self._attribute_cache[attr_name] == value:
643+
if self._attribute_cache.get(attr_name) == value:
644644
return
645645
self._attribute_cache[attr_name] = value
646646

@@ -885,7 +885,7 @@ def listener(vehicle, name, m):
885885
vehicle.notify_attribute_listeners('location.global_relative_frame',
886886
vehicle.location.global_relative_frame)
887887

888-
if self._alt != None or m.alt != 0:
888+
if self._alt is not None or m.alt != 0:
889889
# Require first alt value to be non-0
890890
# TODO is this the proper check to do?
891891
self._alt = m.alt / 1000.0
@@ -1197,7 +1197,7 @@ def listener(self, name, m):
11971197
self.notify_attribute_listeners('armed', self.armed, cache=True)
11981198
self._autopilot_type = m.autopilot
11991199
self._vehicle_type = m.type
1200-
if self._is_mode_available(m.custom_mode, m.base_mode) == False:
1200+
if self._is_mode_available(m.custom_mode, m.base_mode) is False:
12011201
raise APIException("mode (%s, %s) not available on mavlink definition" % (m.custom_mode, m.base_mode))
12021202
if self._autopilot_type == mavutil.mavlink.MAV_AUTOPILOT_PX4:
12031203
self._flightmode = mavutil.interpret_px4_mode(m.base_mode, m.custom_mode)
@@ -1254,7 +1254,7 @@ def listener(self, name, msg):
12541254
# Waypoint send to master
12551255
@self.on_message(['WAYPOINT_REQUEST', 'MISSION_REQUEST'])
12561256
def listener(self, name, msg):
1257-
if self._wp_uploaded != None:
1257+
if self._wp_uploaded is not None:
12581258
wp = self._wploader.wp(msg.seq)
12591259
handler.fix_targets(wp)
12601260
self._master.mav.send(wp)
@@ -1282,7 +1282,7 @@ def listener(_):
12821282
if not self._params_start:
12831283
return
12841284

1285-
if None not in self._params_set and not self._params_loaded:
1285+
if not self._params_loaded and all(x is not None for x in self._params_set):
12861286
self._params_loaded = True
12871287
self.notify_attribute_listeners('parameters', self.parameters)
12881288

@@ -1312,7 +1312,7 @@ def listener(self, name, msg):
13121312
# we lack a param_id.
13131313
try:
13141314
if msg.param_index < msg.param_count and msg:
1315-
if self._params_set[msg.param_index] == None:
1315+
if self._params_set[msg.param_index] is None:
13161316
self._params_last = monotonic.monotonic()
13171317
self._params_duration = start_duration
13181318
self._params_set[msg.param_index] = msg
@@ -1350,7 +1350,7 @@ def listener(_):
13501350
raise APIException('No heartbeat in %s seconds, aborting.' %
13511351
self._heartbeat_error)
13521352
elif monotonic.monotonic() - self._heartbeat_lastreceived > self._heartbeat_warning:
1353-
if self._heartbeat_timeout == False:
1353+
if self._heartbeat_timeout is False:
13541354
errprinter('>>> Link timeout, no heartbeat in last %s seconds' %
13551355
self._heartbeat_warning)
13561356
self._heartbeat_timeout = True
@@ -1673,7 +1673,7 @@ def battery(self):
16731673
"""
16741674
Current system batter status (:py:class:`Battery`).
16751675
"""
1676-
if self._voltage == None or self._current == None or self._level == None:
1676+
if self._voltage is None or self._current is None or self._level is None:
16771677
return None
16781678
return Battery(self._voltage, self._current, self._level)
16791679

@@ -2180,9 +2180,9 @@ def simple_goto(self, location, airspeed=None, groundspeed=None):
21802180
0, 0, 0, location.lat, location.lon,
21812181
alt)
21822182

2183-
if airspeed != None:
2183+
if airspeed is not None:
21842184
self.airspeed = airspeed
2185-
if groundspeed != None:
2185+
if groundspeed is not None:
21862186
self.groundspeed = groundspeed
21872187

21882188
def send_mavlink(self, message):
@@ -2271,7 +2271,7 @@ def initialize(self, rate=4, heartbeat_timeout=30):
22712271
time.sleep(0.1)
22722272

22732273
# Initialize data stream.
2274-
if rate != None:
2274+
if rate is not None:
22752275
self._master.mav.request_data_stream_send(0, 0, mavutil.mavlink.MAV_DATA_STREAM_ALL,
22762276
rate, 1)
22772277

@@ -3035,7 +3035,7 @@ def listener(self, name, m):
30353035
vehicle.initialize(rate=rate, heartbeat_timeout=heartbeat_timeout)
30363036

30373037
if wait_ready:
3038-
if wait_ready == True:
3038+
if wait_ready is True:
30393039
vehicle.wait_ready(still_waiting_interval=still_waiting_interval,
30403040
still_waiting_callback=still_waiting_callback,
30413041
timeout=timeout)

0 commit comments

Comments
 (0)