|
7 | 7 | import time
|
8 | 8 | import threading
|
9 | 9 |
|
| 10 | +from functools import partial |
| 11 | + |
10 | 12 | from MAVProxy.mavproxy import MPState
|
11 | 13 |
|
12 | 14 | from MAVProxy.modules.lib import multiproc
|
@@ -304,7 +306,7 @@ def process_ui_msgs(self):
|
304 | 306 | elif isinstance(msg, terrainnav_msgs.MoveBoundary):
|
305 | 307 | self.move_planner_boundary()
|
306 | 308 | elif isinstance(msg, terrainnav_msgs.Settings):
|
307 |
| - self.edit_settings() |
| 309 | + self.settings_dialog() |
308 | 310 | else:
|
309 | 311 | # TODO: raise an exception
|
310 | 312 | if self.is_debug:
|
@@ -426,10 +428,43 @@ def move_planner_boundary(self):
|
426 | 428 |
|
427 | 429 | self._parent_pipe_send.send(PlannerGridLatLon((lat, lon)))
|
428 | 430 |
|
429 |
| - def edit_settings(self): |
| 431 | + @staticmethod |
| 432 | + def setting_callback(pipe, setting): |
| 433 | + """ |
| 434 | + Called when a setting is updated |
| 435 | +
|
| 436 | + :param pipe: pipe used to send setting to the planner |
| 437 | + :type pipe: multiproc.Pipe |
| 438 | + :param setting: the setting that has changed |
| 439 | + :type setting: MPSetting |
| 440 | + """ |
| 441 | + print(f"setting changed: name: {setting.name}, value: {setting.value}") |
| 442 | + # TODO: find more compact way to ensure all settings are sent to planner |
| 443 | + if setting.name == "loiter_agl_alt": |
| 444 | + pipe.send(PlannerLoiterAglAlt(setting.value)) |
| 445 | + elif setting.name == "loiter_radius": |
| 446 | + pipe.send(PlannerLoiterRadius(setting.value)) |
| 447 | + elif setting.name == "turning_radius": |
| 448 | + pipe.send(PlannerTurningRadius(setting.value)) |
| 449 | + elif setting.name == "climb_angle_deg": |
| 450 | + pipe.send(PlannerClimbAngleDeg(setting.value)) |
| 451 | + elif setting.name == "max_agl_alt": |
| 452 | + pipe.send(PlannerMaxAglAlt(setting.value)) |
| 453 | + elif setting.name == "min_agl_alt": |
| 454 | + pipe.send(PlannerMinAglAlt(setting.value)) |
| 455 | + elif setting.name == "grid_spacing": |
| 456 | + pipe.send(PlannerGridSpacing(setting.value)) |
| 457 | + elif setting.name == "grid_length": |
| 458 | + pipe.send(PlannerGridLength(setting.value)) |
| 459 | + elif setting.name == "time_budget": |
| 460 | + pipe.send(PlannerTimeBudget(setting.value)) |
| 461 | + |
| 462 | + def settings_dialog(self): |
430 | 463 | """
|
431 | 464 | Open the settings dialog
|
432 | 465 | """
|
| 466 | + cb = partial(TerrainNavModule.setting_callback, self._parent_pipe_send) |
| 467 | + self.terrainnav_settings.set_callback(cb) |
433 | 468 | WXSettings(self.terrainnav_settings)
|
434 | 469 |
|
435 | 470 | def draw_circle(self, id, lat, lon, radius, colour):
|
@@ -708,7 +743,7 @@ def generate_waypoints(self):
|
708 | 743 | wp_gen = self.terrainnav_settings.wp_generator
|
709 | 744 | if wp_gen == "SimpleWaypoints":
|
710 | 745 | self.wp_gen_simple_waypoints()
|
711 |
| - elif wp_gen =="UseLoiterToAlt": |
| 746 | + elif wp_gen == "UseLoiterToAlt": |
712 | 747 | self.wp_gen_use_loiter_to_alt()
|
713 | 748 | else:
|
714 | 749 | print(f"[terrainnav] invalid WP generator: {wp_gen}")
|
|
0 commit comments