From b7f01ab9c313f1dc2e37ec2db65e9cd6c4eb447c Mon Sep 17 00:00:00 2001 From: Willian Galvani Date: Thu, 21 Sep 2023 09:46:26 -0300 Subject: [PATCH] send signal_quality via mavlink --- dvl-a50/dvl.py | 2 +- dvl-a50/mavlink2resthelper.py | 10 +++++----- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/dvl-a50/dvl.py b/dvl-a50/dvl.py index e8e4cb8..6989b62 100644 --- a/dvl-a50/dvl.py +++ b/dvl-a50/dvl.py @@ -363,7 +363,7 @@ def handle_velocity(self, data: Dict[str, Any]) -> None: return if self.rangefinder and alt > 0.05: - self.mav.send_rangefinder(alt) + self.mav.send_rangefinder(alt, confidence) if self.should_send == MessageType.POSITION_DELTA: dRoll, dPitch, dYaw = [ diff --git a/dvl-a50/mavlink2resthelper.py b/dvl-a50/mavlink2resthelper.py index 2859220..0d7da6a 100644 --- a/dvl-a50/mavlink2resthelper.py +++ b/dvl-a50/mavlink2resthelper.py @@ -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(int(0), 0) + else: + data = self.rangefinder_template.format(int(distance * 100), int(quality)) post(MAVLINK2REST_URL + "/mavlink", data=data) def set_gps_origin(self, lat, lon):