Skip to content

Commit a037c98

Browse files
committed
Avoid exceptions when wp module is not loaded
1 parent a14f834 commit a037c98

File tree

1 file changed

+14
-8
lines changed

1 file changed

+14
-8
lines changed

Diff for: MAVProxy/modules/mavproxy_console.py

+14-8
Original file line numberDiff line numberDiff line change
@@ -188,6 +188,8 @@ def menu_callback(self, m):
188188

189189
def estimated_time_remaining(self, lat, lon, wpnum, speed):
190190
'''estimate time remaining in mission in seconds'''
191+
if self.module('wp') is None:
192+
return 0
191193
idx = wpnum
192194
if wpnum >= self.module('wp').wploader.count():
193195
return 0
@@ -382,13 +384,14 @@ def handle_vfr_hud(self, msg):
382384
alt = master.field('GPS_RAW_INT', 'alt', 0) / 1.0e3
383385
else:
384386
alt = master.field('GPS_RAW', 'alt', 0)
385-
home = self.module('wp').get_home()
386-
if home is not None:
387-
home_lat = home.x
388-
home_lng = home.y
389-
else:
390-
home_lat = None
391-
home_lng = None
387+
home_lat = None
388+
home_lng = None
389+
if self.module('wp') is not None:
390+
home = self.module('wp').get_home()
391+
if home is not None:
392+
home_lat = home.x
393+
home_lng = home.y
394+
392395
lat = master.field('GLOBAL_POSITION_INT', 'lat', 0) * 1.0e-7
393396
lng = master.field('GLOBAL_POSITION_INT', 'lon', 0) * 1.0e-7
394397
rel_alt = master.field('GLOBAL_POSITION_INT', 'relative_alt', 0) * 1.0e-3
@@ -631,7 +634,10 @@ def handle_heartbeat(self, msg):
631634

632635
def handle_mission_current(self, msg):
633636
master = self.master
634-
wpmax = self.module('wp').wploader.count()
637+
if self.module('wp') is not None:
638+
wpmax = self.module('wp').wploader.count()
639+
else:
640+
wpmax = 0
635641
if wpmax > 0:
636642
wpmax = "/%u" % wpmax
637643
else:

0 commit comments

Comments
 (0)