2013-12-02 07:02:56 -04:00
|
|
|
// -*- 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/>.
|
|
|
|
*/
|
|
|
|
|
|
|
|
#include "AP_RangeFinder_PulsedLightLRF.h"
|
|
|
|
#include <AP_HAL.h>
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
2014-06-27 00:39:52 -03:00
|
|
|
/*
|
|
|
|
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
|
|
|
|
*/
|
|
|
|
AP_RangeFinder_PulsedLightLRF::AP_RangeFinder_PulsedLightLRF(RangeFinder &_ranger, uint8_t instance, RangeFinder::RangeFinder_State &_state) :
|
|
|
|
AP_RangeFinder_Backend(_ranger, instance, _state)
|
2013-12-02 07:02:56 -04:00
|
|
|
{
|
|
|
|
}
|
|
|
|
|
2014-06-27 00:39:52 -03:00
|
|
|
/*
|
|
|
|
detect if a PulsedLight rangefinder is connected. We'll detect by
|
|
|
|
trying to take a reading on I2C. If we get a result the sensor is
|
|
|
|
there.
|
|
|
|
*/
|
|
|
|
bool AP_RangeFinder_PulsedLightLRF::detect(RangeFinder &_ranger, uint8_t instance)
|
2013-12-02 07:02:56 -04:00
|
|
|
{
|
2014-06-27 00:39:52 -03:00
|
|
|
if (!start_reading()) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
// give time for the sensor to process the request
|
|
|
|
hal.scheduler->delay(50);
|
|
|
|
uint16_t reading_cm;
|
|
|
|
return get_reading(reading_cm);
|
2013-12-02 07:02:56 -04:00
|
|
|
}
|
|
|
|
|
2014-06-27 00:39:52 -03:00
|
|
|
// start_reading() - ask sensor to make a range reading
|
|
|
|
bool AP_RangeFinder_PulsedLightLRF::start_reading()
|
2013-12-02 07:02:56 -04:00
|
|
|
{
|
|
|
|
// get pointer to i2c bus semaphore
|
|
|
|
AP_HAL::Semaphore* i2c_sem = hal.i2c->get_semaphore();
|
|
|
|
|
|
|
|
// exit immediately if we can't take the semaphore
|
2014-06-27 00:39:52 -03:00
|
|
|
if (i2c_sem == NULL || !i2c_sem->take(1)) {
|
|
|
|
return false;
|
2013-12-02 07:02:56 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// send command to take reading
|
2014-06-27 00:39:52 -03:00
|
|
|
if (hal.i2c->writeRegister(AP_RANGEFINDER_PULSEDLIGHTLRF_ADDR,
|
|
|
|
AP_RANGEFINDER_PULSEDLIGHTLRF_MEASURE_REG,
|
|
|
|
AP_RANGEFINDER_PULSEDLIGHTLRF_MSRREG_ACQUIRE) != 0) {
|
|
|
|
i2c_sem->give();
|
|
|
|
return false;
|
2013-12-02 07:02:56 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// return semaphore
|
|
|
|
i2c_sem->give();
|
|
|
|
|
2014-06-27 00:39:52 -03:00
|
|
|
return true;
|
2013-12-02 07:02:56 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// read - return last value measured by sensor
|
2014-06-27 00:39:52 -03:00
|
|
|
bool AP_RangeFinder_PulsedLightLRF::get_reading(uint16_t &reading_cm)
|
2013-12-02 07:02:56 -04:00
|
|
|
{
|
|
|
|
uint8_t buff[2];
|
|
|
|
|
|
|
|
// get pointer to i2c bus semaphore
|
|
|
|
AP_HAL::Semaphore* i2c_sem = hal.i2c->get_semaphore();
|
|
|
|
|
|
|
|
// exit immediately if we can't take the semaphore
|
2014-06-27 00:39:52 -03:00
|
|
|
if (i2c_sem == NULL || !i2c_sem->take(1)) {
|
|
|
|
return false;
|
2013-12-02 07:02:56 -04:00
|
|
|
}
|
|
|
|
|
2014-07-17 11:34:13 -03:00
|
|
|
// read the high and low byte distance registers
|
2014-06-27 00:39:52 -03:00
|
|
|
if (hal.i2c->readRegisters(AP_RANGEFINDER_PULSEDLIGHTLRF_ADDR,
|
2014-07-17 11:34:13 -03:00
|
|
|
AP_RANGEFINDER_PULSEDLIGHTLRF_DISTHIGH_REG, 2, &buff[0]) != 0) {
|
2014-06-27 00:39:52 -03:00
|
|
|
i2c_sem->give();
|
|
|
|
return false;
|
2013-12-02 07:02:56 -04:00
|
|
|
}
|
|
|
|
|
2014-06-27 00:39:52 -03:00
|
|
|
// combine results into distance
|
|
|
|
reading_cm = ((uint16_t)buff[0]) << 8 | buff[1];
|
2013-12-02 07:02:56 -04:00
|
|
|
|
|
|
|
// return semaphore
|
|
|
|
i2c_sem->give();
|
|
|
|
|
|
|
|
// kick off another reading for next time
|
|
|
|
// To-Do: replace this with continuous mode
|
2014-06-27 00:39:52 -03:00
|
|
|
hal.scheduler->delay_microseconds(200);
|
|
|
|
start_reading();
|
2013-12-02 07:02:56 -04:00
|
|
|
|
2014-06-27 00:39:52 -03:00
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
update the state of the sensor
|
|
|
|
*/
|
|
|
|
void AP_RangeFinder_PulsedLightLRF::update(void)
|
|
|
|
{
|
2015-04-13 03:07:32 -03:00
|
|
|
if (get_reading(state.distance_cm)) {
|
|
|
|
// update range_valid state based on distance measured
|
|
|
|
update_status();
|
|
|
|
} else {
|
|
|
|
set_status(RangeFinder::RangeFinder_NoData);
|
|
|
|
}
|
2013-12-02 07:02:56 -04:00
|
|
|
}
|