2014-06-26 23:56:50 -03:00
|
|
|
/*
|
|
|
|
This program is free software: you can redistribute it and/or modify
|
|
|
|
it under the terms of the GNU General Public License as published by
|
|
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
|
|
(at your option) any later version.
|
|
|
|
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
|
|
GNU General Public License for more details.
|
|
|
|
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
|
|
|
|
2015-08-11 03:28:45 -03:00
|
|
|
#include <AP_Common/AP_Common.h>
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2014-06-26 23:56:50 -03:00
|
|
|
#include "RangeFinder.h"
|
|
|
|
#include "RangeFinder_Backend.h"
|
|
|
|
|
2016-11-04 00:35:41 -03:00
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
2014-06-26 23:56:50 -03:00
|
|
|
/*
|
|
|
|
base class constructor.
|
|
|
|
This incorporates initialisation as well.
|
|
|
|
*/
|
2018-07-04 11:22:17 -03:00
|
|
|
AP_RangeFinder_Backend::AP_RangeFinder_Backend(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) :
|
|
|
|
state(_state),
|
|
|
|
params(_params)
|
2014-06-26 23:56:50 -03:00
|
|
|
{
|
2019-04-08 06:42:46 -03:00
|
|
|
_backend_type = (RangeFinder::RangeFinder_Type)params.type.get();
|
2014-06-26 23:56:50 -03:00
|
|
|
}
|
2015-04-13 03:03:19 -03:00
|
|
|
|
2018-08-27 03:11:09 -03:00
|
|
|
MAV_DISTANCE_SENSOR AP_RangeFinder_Backend::get_mav_distance_sensor_type() const {
|
2018-07-04 11:22:17 -03:00
|
|
|
if (params.type == RangeFinder::RangeFinder_TYPE_NONE) {
|
2018-08-27 03:11:09 -03:00
|
|
|
return MAV_DISTANCE_SENSOR_UNKNOWN;
|
|
|
|
}
|
|
|
|
return _get_mav_distance_sensor_type();
|
|
|
|
}
|
|
|
|
|
|
|
|
RangeFinder::RangeFinder_Status AP_RangeFinder_Backend::status() const {
|
2018-07-04 11:22:17 -03:00
|
|
|
if (params.type == RangeFinder::RangeFinder_TYPE_NONE) {
|
2018-08-27 03:11:09 -03:00
|
|
|
// turned off at runtime?
|
|
|
|
return RangeFinder::RangeFinder_NotConnected;
|
|
|
|
}
|
|
|
|
return state.status;
|
|
|
|
}
|
|
|
|
|
|
|
|
// true if sensor is returning data
|
|
|
|
bool AP_RangeFinder_Backend::has_data() const {
|
|
|
|
return ((state.status != RangeFinder::RangeFinder_NotConnected) &&
|
|
|
|
(state.status != RangeFinder::RangeFinder_NoData));
|
|
|
|
}
|
|
|
|
|
2015-04-13 03:03:19 -03:00
|
|
|
// update status based on distance measurement
|
|
|
|
void AP_RangeFinder_Backend::update_status()
|
|
|
|
{
|
|
|
|
// check distance
|
2018-07-04 11:22:17 -03:00
|
|
|
if ((int16_t)state.distance_cm > params.max_distance_cm) {
|
2015-04-13 03:03:19 -03:00
|
|
|
set_status(RangeFinder::RangeFinder_OutOfRangeHigh);
|
2018-07-04 11:22:17 -03:00
|
|
|
} else if ((int16_t)state.distance_cm < params.min_distance_cm) {
|
2015-04-13 03:03:19 -03:00
|
|
|
set_status(RangeFinder::RangeFinder_OutOfRangeLow);
|
|
|
|
} else {
|
|
|
|
set_status(RangeFinder::RangeFinder_Good);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// set status and update valid count
|
2017-08-08 02:54:09 -03:00
|
|
|
void AP_RangeFinder_Backend::set_status(RangeFinder::RangeFinder_Status _status)
|
2015-04-13 03:03:19 -03:00
|
|
|
{
|
2017-08-08 02:54:09 -03:00
|
|
|
state.status = _status;
|
2015-04-13 03:03:19 -03:00
|
|
|
|
|
|
|
// update valid count
|
2017-08-08 02:54:09 -03:00
|
|
|
if (_status == RangeFinder::RangeFinder_Good) {
|
2015-04-13 03:03:19 -03:00
|
|
|
if (state.range_valid_count < 10) {
|
|
|
|
state.range_valid_count++;
|
|
|
|
}
|
|
|
|
} else {
|
|
|
|
state.range_valid_count = 0;
|
|
|
|
}
|
|
|
|
}
|
2017-08-07 01:20:46 -03:00
|
|
|
|