AP_RangFinder: support various maxbotix serial sonar

This commit is contained in:
chobits 2022-01-13 10:48:24 +08:00 committed by Andrew Tridgell
parent 09dac0cc8a
commit 051104a3f7
3 changed files with 11 additions and 3 deletions

View File

@ -24,6 +24,14 @@
extern const AP_HAL::HAL& hal;
AP_RangeFinder_MaxsonarSerialLV::AP_RangeFinder_MaxsonarSerialLV(
RangeFinder::RangeFinder_State &_state,
AP_RangeFinder_Params &_params):
AP_RangeFinder_Backend_Serial(_state, _params)
{
params.scaling.set_default(0.0254f);
}
// read - return last value measured by sensor
bool AP_RangeFinder_MaxsonarSerialLV::get_reading(float &reading_m)
{
@ -56,7 +64,7 @@ bool AP_RangeFinder_MaxsonarSerialLV::get_reading(float &reading_m)
}
// This sonar gives the metrics in inches, so we have to transform this to meters
reading_m = (2.54f * 0.01f) * (float(sum) / count);
reading_m = params.scaling * (float(sum) / count);
return true;
}

View File

@ -8,7 +8,7 @@ class AP_RangeFinder_MaxsonarSerialLV : public AP_RangeFinder_Backend_Serial
public:
using AP_RangeFinder_Backend_Serial::AP_RangeFinder_Backend_Serial;
AP_RangeFinder_MaxsonarSerialLV(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params);
protected:

View File

@ -19,7 +19,7 @@ const AP_Param::GroupInfo AP_RangeFinder_Params::var_info[] = {
// @Param: SCALING
// @DisplayName: Rangefinder scaling
// @Description: Scaling factor between rangefinder reading and distance. For the linear and inverted functions this is in meters per volt. For the hyperbolic function the units are meterVolts.
// @Description: Scaling factor between rangefinder reading and distance. For the linear and inverted functions this is in meters per volt. For the hyperbolic function the units are meterVolts. For Maxbotix serial sonar this is unit conversion to meters.
// @Units: m/V
// @Increment: 0.001
// @User: Standard