Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

send signal_quality via mavlink #34

Open
wants to merge 4 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
15 changes: 14 additions & 1 deletion dvl-a50/dvl.py
Original file line number Diff line number Diff line change
Expand Up @@ -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
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'm a bit confused as to why this is 0 if the default is 80 - I think it could make more sense to specify a meaningful value here and then use that as the fallback when loading settings.


def __init__(self, orientation=DVL_DOWN) -> None:
threading.Thread.__init__(self)
Expand All @@ -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.")
Expand Down Expand Up @@ -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,
}
)
)
Expand All @@ -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
Expand Down Expand Up @@ -273,6 +277,14 @@ def set_enabled(self, enable: bool) -> bool:
self.save_settings()
return True

def set_confidence_cutoff(self, cutoff: int) -> bool:
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

does it make sense to return a value at all ?

"""
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
Expand Down Expand Up @@ -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)
Comment on lines +397 to +398
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Could this not be another and in the line before, and drop an indentation level?


position_delta = [0, 0, 0]
attitude_delta = [0, 0, 0]
Expand Down
10 changes: 10 additions & 0 deletions dvl-a50/main.py
Original file line number Diff line number Diff line change
Expand Up @@ -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
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
Enables/Disables the DVL driver
Sets the required confidence for sending rangefinder distance estimates.

"""
return self.dvl.set_confidence_cutoff(int(cutoff))

def set_orientation(self, orientation: int) -> bool:
"""
Sets the DVL mounting orientation:
Expand Down Expand Up @@ -87,6 +93,10 @@ def get_status():
def set_enabled(enable: str):
return str(api.set_enabled(enable))

@app.route("/cutoff/<cutoff>")
def set_cutoff(cutoff: int):
return str(api.set_cutoff(cutoff))

@app.route("/use_as_rangefinder/<enable>")
def set_use_rangefinder(enable: str):
return str(api.set_use_as_rangefinder(enable))
Expand Down
12 changes: 6 additions & 6 deletions dvl-a50/mavlink2resthelper.py
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

If possible it would be helpful to specify the unit here in a comment, and some reasoning behind the value, but ideally the number would be settable from the frontend and/or dynamically determined by the device type or something (rather than hardcoding something arbitrary).

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Hmmm... the correct value for the A50 is 5000 cm, and for the A125 is 12500 cm. Maybe there's a way to get the model # from the data stream? In any case 50000 cm seems too high.

The autopilot code is using min(DISTANCE_SENSOR.max_distance, RNGFNDx_MAX_CM), so the pilot can control the max and min using the RNGFNDx parameters. Same with the minimum. So I don't see huge value in letting the pilot set this value. https://github.com/ArduPilot/ardupilot/blob/9986fb972635016171235750a465adc0d0174ba0/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.cpp#L48

P.S. the default RNGFNDx_MAX_CM is 700 cm, so the pilot will need to tweak this parameter to get RNG_HOLD to work > 7m above the seafloor.

"current_distance": {0},
"mavtype": {{
"type": "MAV_DISTANCE_SENSOR_LASER"
Expand All @@ -170,7 +170,7 @@ def __init__(self, vehicle: int = 1, component: int = 1):
0.0,
0.0
],
"signal_quality": 0
"signal_quality": {1}
}}
}}
"""
Expand Down Expand Up @@ -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):
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

quality_percentage ?

"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):
Expand Down
18 changes: 16 additions & 2 deletions dvl-a50/static/index.html
Original file line number Diff line number Diff line change
Expand Up @@ -38,12 +38,18 @@ <h1>DVL Configuration</h1>
<br />
<v-row>
<v-col>
<v-card height="650">
<v-card height="650" width="300">
<h2>Settings</h2>
<v-switch v-model="this.enabled" inset :label="`Enable DVL driver`" @change="setDvlEnabled($event)"></v-switch>
<v-switch v-model="this.rangefinder" inset :label="`Send range data through MAVLink`" @change="setDvlAsRangefinder($event)"></v-switch>
<v-btn id="btn-load-dvl" type="button" class="btn btn-primary" @click="loadParams('dvl');">Load parameters for DVL</v-btn>
<v-btn id="btn-load-dvl-gps" type="button" class="btn btn-primary" @click="loadParams('dvl_gps');">Load parameters for DVL+GPS</v-btn>
<label for="confidence-cutoff">Confidence Cutoff:</label>
<v-slider id="confidence-cutoff" @change="setConfidenceCutoff" v-model="confidenceCutoff" :min="0" :max="100" :step="1">
<template #prepend>
<span>{{ confidenceCutoff }}</span>
</template>
</v-slider>
<h2>Status</h2>
<div>
<textarea readonly style="width:100%;"
Expand Down Expand Up @@ -133,10 +139,17 @@ <h2>Water Linked DVL Configuration Page</h2>
orientationOptions: {
"Downwards (LED pointing forward)": 1,
"Forward (Experimental)": 2,
}
},
confidenceCutoff: 10,
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Should this perhaps match the DvlDriver default? Or is it immediately overwritten by fetching from the backend or something? It would be weird if the displayed value doesn't match the internal one.

}
},
methods: {
setConfidenceCutoff(value) {
const request = new XMLHttpRequest();
request.timeout = 800;
request.open('GET', 'cutoff/' + value, true);
request.send();
},
updateDvlStatus() {
axios.get('/get_status', { timeout: 1000 })
.then((response) => {
Expand All @@ -156,6 +169,7 @@ <h2>Water Linked DVL Configuration Page</h2>
if (this.newHostname == null) {
this.newHostname = data.hostname
}
this.confidenceCutoff = data.confidence_cutoff
})
.catch((error) => {
this.status = `Unable to talk to DVL service: ${error}`
Expand Down
Loading