|
| 1 | +#!/usr/bin/env python3 |
| 2 | +''' |
| 3 | +Soaring Module |
| 4 | +Ryan Friedman |
| 5 | +
|
| 6 | +This module displays the estimated soaring thermals on the map. |
| 7 | +A circle is drawn with the estimated radius from ArduSoar's estimated thermal location. |
| 8 | +
|
| 9 | +Note that this module uses NAMED_VALUE_FLOAT messages from the autopilot, |
| 10 | +a temporary measure until a proper mavlink message is decided upon. |
| 11 | +
|
| 12 | +AP_FLAKE8_CLEAN |
| 13 | +''' |
| 14 | + |
| 15 | +from MAVProxy.modules.lib import mp_module, mp_util |
| 16 | +from MAVProxy.modules.mavproxy_map import mp_slipmap |
| 17 | + |
| 18 | +import time |
| 19 | + |
| 20 | + |
| 21 | +class soar(mp_module.MPModule): |
| 22 | + _SOAR_THERMAL_MAP_OBJ_ID = "soar-thermal" |
| 23 | + _CLEAR_STALE_THERMAL_TIME = 5.0 |
| 24 | + |
| 25 | + def __init__(self, mpstate): |
| 26 | + """Initialise module""" |
| 27 | + super(soar, self).__init__(mpstate, "soar", "") |
| 28 | + self._strength = None |
| 29 | + self._radius = None |
| 30 | + self._x = None |
| 31 | + self._y = None |
| 32 | + self._last_draw_time = time.time() |
| 33 | + |
| 34 | + def mavlink_packet(self, m): |
| 35 | + '''handle mavlink packets''' |
| 36 | + |
| 37 | + if m.get_type() == 'NAMED_VALUE_FLOAT' and m.name.startswith("SOAR"): |
| 38 | + if m.name == "SOAREKFX0": |
| 39 | + self._strength = m.value |
| 40 | + elif m.name == "SOAREKFX1": |
| 41 | + self._radius = m.value |
| 42 | + elif m.name == "SOAREKFX2": |
| 43 | + self._x = m.value |
| 44 | + elif m.name == "SOAREKFX3": |
| 45 | + self._y = m.value |
| 46 | + else: |
| 47 | + raise NotImplementedError(m.name) |
| 48 | + |
| 49 | + self.draw_thermal_estimate() |
| 50 | + |
| 51 | + def idle_task(self): |
| 52 | + '''called rapidly by mavproxy''' |
| 53 | + |
| 54 | + if time.time() - self._last_draw_time > self._CLEAR_STALE_THERMAL_TIME: |
| 55 | + self.clear_thermal_estimate() |
| 56 | + |
| 57 | + def draw_thermal_estimate(self): |
| 58 | + |
| 59 | + if self._radius is None: |
| 60 | + return |
| 61 | + if self._x is None: |
| 62 | + return |
| 63 | + if self._y is None: |
| 64 | + return |
| 65 | + |
| 66 | + wp_module = self.module('wp') |
| 67 | + if wp_module is None: |
| 68 | + return |
| 69 | + home = wp_module.get_home() |
| 70 | + if home is None: |
| 71 | + return |
| 72 | + |
| 73 | + home_lat = home.x |
| 74 | + home_lng = home.y |
| 75 | + |
| 76 | + (thermal_lat, thermal_lon) = mp_util.gps_offset(home_lat, home_lng, self._y, self._x) |
| 77 | + |
| 78 | + slipcircle = mp_slipmap.SlipCircle( |
| 79 | + self._SOAR_THERMAL_MAP_OBJ_ID, # key |
| 80 | + "thermals", # layer |
| 81 | + (thermal_lat, thermal_lon), # latlon |
| 82 | + self._radius, # radius |
| 83 | + (0, 255, 255), |
| 84 | + linewidth=2) |
| 85 | + for mp in self.module_matching('map*'): |
| 86 | + self._last_draw_time = time.time() |
| 87 | + mp.map.add_object(slipcircle) |
| 88 | + |
| 89 | + def clear_thermal_estimate(self): |
| 90 | + for mp in self.module_matching('map*'): |
| 91 | + mp.map.remove_object(self._SOAR_THERMAL_MAP_OBJ_ID) |
| 92 | + |
| 93 | + |
| 94 | +def init(mpstate): |
| 95 | + '''initialise module''' |
| 96 | + return soar(mpstate) |
0 commit comments