AP_RangeFinder: MAVLink: use larger of min ranges / smaller of max ranges

This commit is contained in:
Peter Barker 2020-12-25 19:38:49 +11:00 committed by Peter Barker
parent 81ab322daa
commit 496267115c
2 changed files with 26 additions and 2 deletions

View File

@ -34,6 +34,30 @@ void AP_RangeFinder_MAVLink::handle_msg(const mavlink_message_t &msg)
}
}
int16_t AP_RangeFinder_MAVLink::max_distance_cm() const
{
if (_max_distance_cm == 0 && _min_distance_cm == 0) {
// we assume if both of these are zero that we ignore both
return params.max_distance_cm;
}
if (params.max_distance_cm < _max_distance_cm) {
return params.max_distance_cm;
}
return _max_distance_cm;
}
int16_t AP_RangeFinder_MAVLink::min_distance_cm() const
{
if (_max_distance_cm == 0 && _min_distance_cm == 0) {
// we assume if both of these are zero that we ignore both
return params.min_distance_cm;
}
if (params.min_distance_cm > _min_distance_cm) {
return params.min_distance_cm;
}
return _min_distance_cm;
}
/*
update the state of the sensor
*/

View File

@ -23,8 +23,8 @@ public:
// Get update from mavlink
void handle_msg(const mavlink_message_t &msg) override;
int16_t max_distance_cm() const override { return _max_distance_cm; }
int16_t min_distance_cm() const override { return _min_distance_cm; }
int16_t max_distance_cm() const override;
int16_t min_distance_cm() const override;
protected: