diff --git a/dvl-a50/dvl.py b/dvl-a50/dvl.py index e215f2f..1f12d8e 100644 --- a/dvl-a50/dvl.py +++ b/dvl-a50/dvl.py @@ -63,6 +63,7 @@ class DvlDriver(threading.Thread): last_temperature_check_time = 0 temperature_check_interval_s = 30 temperature_too_hot = 45 + confidence_cutoff = 0 def __init__(self, orientation=DVL_DOWN) -> None: threading.Thread.__init__(self) @@ -88,6 +89,7 @@ def load_settings(self) -> None: self.origin = data["origin"] self.rangefinder = data["rangefinder"] self.should_send = data["should_send"] + self.confidence_cutoff = data.get("confidence_cutoff", 80) logger.debug("Loaded settings: ", data) except FileNotFoundError: logger.warning("Settings file not found, using default.") @@ -120,6 +122,7 @@ def ensure_dir(file_path) -> None: "hostname": self.hostname, "rangefinder": self.rangefinder, "should_send": self.should_send, + "confidence_cutoff": self.confidence_cutoff, } ) ) @@ -136,6 +139,7 @@ def get_status(self) -> dict: "origin": self.origin, "rangefinder": self.rangefinder, "should_send": self.should_send, + "confidence_cutoff": self.confidence_cutoff, } @property @@ -273,6 +277,14 @@ def set_enabled(self, enable: bool) -> bool: self.save_settings() return True + def set_confidence_cutoff(self, cutoff: int) -> bool: + """ + Enables/disables the driver + """ + self.confidence_cutoff = max(5, min(100, cutoff)) + self.save_settings() + return True + def set_use_as_rangefinder(self, enable: bool) -> bool: """ Enables/disables DISTANCE_SENSOR messages @@ -382,7 +394,8 @@ def handle_velocity(self, data: Dict[str, Any]) -> None: return if self.rangefinder and alt > 0.05: - self.mav.send_rangefinder(alt) + if confidence >= self.confidence_cutoff: + self.mav.send_rangefinder(alt, confidence) position_delta = [0, 0, 0] attitude_delta = [0, 0, 0] diff --git a/dvl-a50/main.py b/dvl-a50/main.py index f4774af..c80a526 100755 --- a/dvl-a50/main.py +++ b/dvl-a50/main.py @@ -35,6 +35,12 @@ def set_enabled(self, enabled: str) -> bool: return self.dvl.set_enabled(enabled == "true") return False + def set_cutoff(self, cutoff: int) -> bool: + """ + Enables/Disables the DVL driver + """ + return self.dvl.set_confidence_cutoff(int(cutoff)) + def set_orientation(self, orientation: int) -> bool: """ Sets the DVL mounting orientation: @@ -87,6 +93,10 @@ def get_status(): def set_enabled(enable: str): return str(api.set_enabled(enable)) + @app.route("/cutoff/") + def set_cutoff(cutoff: int): + return str(api.set_cutoff(cutoff)) + @app.route("/use_as_rangefinder/") def set_use_rangefinder(enable: str): return str(api.set_use_as_rangefinder(enable)) diff --git a/dvl-a50/mavlink2resthelper.py b/dvl-a50/mavlink2resthelper.py index 9f29166..afb06cd 100644 --- a/dvl-a50/mavlink2resthelper.py +++ b/dvl-a50/mavlink2resthelper.py @@ -152,7 +152,7 @@ def __init__(self, vehicle: int = 1, component: int = 1): "type": "DISTANCE_SENSOR", "time_boot_ms": 0, "min_distance": 0, - "max_distance": 5000, + "max_distance": 50000, "current_distance": {0}, "mavtype": {{ "type": "MAV_DISTANCE_SENSOR_LASER" @@ -170,7 +170,7 @@ def __init__(self, vehicle: int = 1, component: int = 1): 0.0, 0.0 ], - "signal_quality": 0 + "signal_quality": {1} }} }} """ @@ -352,12 +352,12 @@ def send_vision_position_estimate( ) logger.info(post(MAVLINK2REST_URL + "/mavlink", data=data)) - def send_rangefinder(self, distance: float): + def send_rangefinder(self, distance: float, quality: float): "Sends message DISTANCE_SENSOR to flight controller" if distance == -1: - return - data = self.rangefinder_template.format(int(distance * 100)) - + data = self.rangefinder_template.format(0, 0) + else: + data = self.rangefinder_template.format(int(distance * 100), int(max(1, quality))) post(MAVLINK2REST_URL + "/mavlink", data=data) def set_gps_origin(self, lat, lon): diff --git a/dvl-a50/static/index.html b/dvl-a50/static/index.html index 871bb38..1f67069 100644 --- a/dvl-a50/static/index.html +++ b/dvl-a50/static/index.html @@ -38,12 +38,18 @@

DVL Configuration


- +

Settings

Load parameters for DVL Load parameters for DVL+GPS + + + +

Status