You can not select more than 25 topics
Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.
74 lines
2.3 KiB
74 lines
2.3 KiB
9 years ago
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||
|
/*
|
||
|
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/>.
|
||
|
*/
|
||
|
|
||
9 years ago
|
#include "AP_RangeFinder_MAVLink.h"
|
||
9 years ago
|
#include <AP_HAL/AP_HAL.h>
|
||
|
|
||
|
|
||
|
|
||
|
extern const AP_HAL::HAL& hal;
|
||
|
|
||
9 years ago
|
/*
|
||
9 years ago
|
The constructor also initialises the rangefinder. Note that this
|
||
|
constructor is not called until detect() returns true, so we
|
||
|
already know that we should setup the rangefinder
|
||
|
*/
|
||
9 years ago
|
AP_RangeFinder_MAVLink::AP_RangeFinder_MAVLink(RangeFinder &_ranger, uint8_t instance, RangeFinder::RangeFinder_State &_state) :
|
||
9 years ago
|
AP_RangeFinder_Backend(_ranger, instance, _state)
|
||
|
{
|
||
|
last_update_ms = AP_HAL::millis();
|
||
9 years ago
|
distance_cm = 0;
|
||
9 years ago
|
}
|
||
|
|
||
9 years ago
|
/*
|
||
|
detect if a MAVLink rangefinder is connected. We'll detect by
|
||
9 years ago
|
checking a paramter.
|
||
|
*/
|
||
9 years ago
|
bool AP_RangeFinder_MAVLink::detect(RangeFinder &_ranger, uint8_t instance)
|
||
9 years ago
|
{
|
||
9 years ago
|
// Assume that if the user set the RANGEFINDER_TYPE parameter to MAVLink,
|
||
|
// there is an attached MAVLink rangefinder
|
||
9 years ago
|
return true;
|
||
|
}
|
||
|
|
||
|
/*
|
||
|
Set the distance based on a MAVLINK message
|
||
|
*/
|
||
9 years ago
|
void AP_RangeFinder_MAVLink::handle_msg(mavlink_message_t *msg)
|
||
9 years ago
|
{
|
||
|
mavlink_distance_sensor_t packet;
|
||
|
mavlink_msg_distance_sensor_decode(msg, &packet);
|
||
|
|
||
|
last_update_ms = AP_HAL::millis();
|
||
9 years ago
|
distance_cm = packet.current_distance;
|
||
9 years ago
|
}
|
||
|
|
||
9 years ago
|
/*
|
||
9 years ago
|
update the state of the sensor
|
||
|
*/
|
||
9 years ago
|
void AP_RangeFinder_MAVLink::update(void)
|
||
9 years ago
|
{
|
||
|
//Time out on incoming data; if we don't get new
|
||
|
//data in 500ms, dump it
|
||
9 years ago
|
if(AP_HAL::millis() - last_update_ms > AP_RANGEFINDER_MAVLINK_TIMEOUT_MS) {
|
||
9 years ago
|
set_status(RangeFinder::RangeFinder_NoData);
|
||
|
state.distance_cm = 0;
|
||
|
} else {
|
||
|
set_status(RangeFinder::RangeFinder_Good);
|
||
9 years ago
|
state.distance_cm = distance_cm;
|
||
9 years ago
|
}
|
||
|
}
|