2016-12-23 02:03:21 -04: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/>.
|
|
|
|
*/
|
|
|
|
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#include "AP_Proximity_MAV.h"
|
|
|
|
#include <AP_SerialManager/AP_SerialManager.h>
|
|
|
|
#include <ctype.h>
|
|
|
|
#include <stdio.h>
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
|
|
|
/*
|
|
|
|
The constructor also initialises the proximity sensor. Note that this
|
|
|
|
constructor is not called until detect() returns true, so we
|
|
|
|
already know that we should setup the proximity sensor
|
|
|
|
*/
|
|
|
|
AP_Proximity_MAV::AP_Proximity_MAV(AP_Proximity &_frontend,
|
|
|
|
AP_Proximity::Proximity_State &_state) :
|
|
|
|
AP_Proximity_Backend(_frontend, _state)
|
|
|
|
{
|
|
|
|
}
|
|
|
|
|
|
|
|
// update the state of the sensor
|
|
|
|
void AP_Proximity_MAV::update(void)
|
|
|
|
{
|
|
|
|
// check for timeout and set health status
|
2017-04-12 05:59:40 -03:00
|
|
|
if ((_last_update_ms == 0 || (AP_HAL::millis() - _last_update_ms > PROXIMITY_MAV_TIMEOUT_MS)) &&
|
|
|
|
(_last_upward_update_ms == 0 || (AP_HAL::millis() - _last_upward_update_ms > PROXIMITY_MAV_TIMEOUT_MS))) {
|
2016-12-23 02:03:21 -04:00
|
|
|
set_status(AP_Proximity::Proximity_NoData);
|
|
|
|
} else {
|
|
|
|
set_status(AP_Proximity::Proximity_Good);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2017-01-16 02:58:14 -04:00
|
|
|
// get distance upwards in meters. returns true on success
|
|
|
|
bool AP_Proximity_MAV::get_upward_distance(float &distance) const
|
|
|
|
{
|
|
|
|
if ((_last_upward_update_ms != 0) && (AP_HAL::millis() - _last_upward_update_ms <= PROXIMITY_MAV_TIMEOUT_MS)) {
|
|
|
|
distance = _distance_upward;
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2016-12-23 02:03:21 -04:00
|
|
|
// handle mavlink DISTANCE_SENSOR messages
|
|
|
|
void AP_Proximity_MAV::handle_msg(mavlink_message_t *msg)
|
|
|
|
{
|
|
|
|
mavlink_distance_sensor_t packet;
|
|
|
|
mavlink_msg_distance_sensor_decode(msg, &packet);
|
|
|
|
|
|
|
|
// store distance to appropriate sector based on orientation field
|
|
|
|
if (packet.orientation <= MAV_SENSOR_ROTATION_YAW_315) {
|
|
|
|
uint8_t sector = packet.orientation;
|
|
|
|
_angle[sector] = sector * 45;
|
|
|
|
_distance[sector] = packet.current_distance / 100.0f;
|
|
|
|
_distance_min = packet.min_distance / 100.0f;
|
|
|
|
_distance_max = packet.max_distance / 100.0f;
|
2017-06-05 00:20:20 -03:00
|
|
|
_distance_valid[sector] = (_distance[sector] >= _distance_min) && (_distance[sector] <= _distance_max);
|
2016-12-23 02:03:21 -04:00
|
|
|
_last_update_ms = AP_HAL::millis();
|
2017-01-09 23:09:18 -04:00
|
|
|
update_boundary_for_sector(sector);
|
2016-12-23 02:03:21 -04:00
|
|
|
}
|
2017-01-16 02:58:14 -04:00
|
|
|
|
|
|
|
// store upward distance
|
|
|
|
if (packet.orientation == MAV_SENSOR_ROTATION_PITCH_90) {
|
|
|
|
_distance_upward = packet.current_distance / 100.0f;
|
|
|
|
_last_upward_update_ms = AP_HAL::millis();
|
|
|
|
}
|
2016-12-23 02:03:21 -04:00
|
|
|
}
|