2015-04-19 10:26:48 -03: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/>.
|
|
|
|
*/
|
|
|
|
|
|
|
|
/*
|
|
|
|
* AP_OpticalFlow_Linux.cpp - ardupilot library for the PX4Flow sensor.
|
|
|
|
* inspired by the PX4Firmware code.
|
2016-04-01 18:11:18 -03:00
|
|
|
*
|
2015-04-19 10:26:48 -03:00
|
|
|
* @author: Víctor Mayoral Vilches
|
|
|
|
*
|
2016-04-01 18:11:18 -03:00
|
|
|
* Address range 0x42 - 0x49
|
2015-04-19 10:26:48 -03:00
|
|
|
*/
|
|
|
|
|
2016-04-01 18:11:18 -03:00
|
|
|
#include <utility>
|
|
|
|
|
2015-08-11 03:28:44 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2016-04-01 18:11:18 -03:00
|
|
|
|
2015-04-19 10:26:48 -03:00
|
|
|
#include "OpticalFlow.h"
|
|
|
|
|
2015-08-05 07:26:59 -03:00
|
|
|
#define PX4FLOW_DEBUG 1
|
2015-04-19 10:26:48 -03:00
|
|
|
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
2015-08-05 07:26:59 -03:00
|
|
|
|
|
|
|
#define PX4FLOW_REG 0x16 // Measure Register 22
|
|
|
|
#define I2C_FRAME_SIZE (sizeof(i2c_frame))
|
|
|
|
#define I2C_INTEGRAL_FRAME_SIZE (sizeof(i2c_integral_frame))
|
|
|
|
|
2015-04-19 10:26:48 -03:00
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
2016-04-01 18:11:18 -03:00
|
|
|
AP_OpticalFlow_Linux::AP_OpticalFlow_Linux(OpticalFlow &_frontend, AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
|
|
|
|
: OpticalFlow_backend(_frontend)
|
|
|
|
, _dev(std::move(dev))
|
2015-04-19 10:26:48 -03:00
|
|
|
{}
|
|
|
|
|
|
|
|
void AP_OpticalFlow_Linux::init(void)
|
|
|
|
{
|
2015-08-05 07:26:59 -03:00
|
|
|
// only initialise once
|
|
|
|
if (initialised) {
|
|
|
|
return;
|
|
|
|
}
|
2015-04-19 10:26:48 -03:00
|
|
|
|
2015-08-05 07:26:59 -03:00
|
|
|
// take i2c bus sempahore
|
2016-04-01 18:11:18 -03:00
|
|
|
if (!_dev->get_semaphore()->take(200)) {
|
2015-08-05 07:26:59 -03:00
|
|
|
return;
|
|
|
|
}
|
2015-04-19 10:26:48 -03:00
|
|
|
|
2015-08-05 07:26:59 -03:00
|
|
|
// read from flow sensor to ensure it is not a ll40ls Lidar (which can be on 0x42)
|
|
|
|
// read I2C_FRAME_SIZE bytes, the ll40ls will error whereas the flow happily returns data
|
|
|
|
uint8_t val[I2C_FRAME_SIZE];
|
2016-04-01 18:11:18 -03:00
|
|
|
if (!_dev->read_registers(0, val, I2C_FRAME_SIZE)) {
|
|
|
|
goto fail;
|
2015-08-05 07:26:59 -03:00
|
|
|
}
|
2015-04-19 10:26:48 -03:00
|
|
|
|
2015-08-05 07:26:59 -03:00
|
|
|
// success
|
|
|
|
initialised = true;
|
2016-04-01 18:11:18 -03:00
|
|
|
|
|
|
|
fail:
|
|
|
|
_dev->get_semaphore()->give();
|
2015-04-19 10:26:48 -03:00
|
|
|
}
|
|
|
|
|
2015-08-05 07:26:59 -03:00
|
|
|
bool AP_OpticalFlow_Linux::request_measurement()
|
2015-04-19 10:26:48 -03:00
|
|
|
{
|
2015-08-05 07:26:59 -03:00
|
|
|
// send measure request to sensor
|
2016-04-01 18:11:18 -03:00
|
|
|
return _dev->write_register(PX4FLOW_REG, 0);
|
2015-08-05 07:26:59 -03:00
|
|
|
}
|
2015-04-19 10:26:48 -03:00
|
|
|
|
2015-08-05 07:26:59 -03:00
|
|
|
bool AP_OpticalFlow_Linux::read(optical_flow_s* report)
|
|
|
|
{
|
|
|
|
// take i2c bus sempahore (non blocking)
|
2016-04-01 18:11:18 -03:00
|
|
|
if (!_dev->get_semaphore()->take_nonblocking()) {
|
2015-08-05 07:26:59 -03:00
|
|
|
return false;
|
2015-04-19 10:26:48 -03:00
|
|
|
}
|
|
|
|
|
2015-08-05 07:26:59 -03:00
|
|
|
// request measurement
|
|
|
|
request_measurement();
|
2015-04-19 10:26:48 -03:00
|
|
|
|
2015-08-05 07:26:59 -03:00
|
|
|
uint8_t val[I2C_FRAME_SIZE + I2C_INTEGRAL_FRAME_SIZE] = {};
|
|
|
|
i2c_integral_frame f_integral;
|
2015-04-19 10:26:48 -03:00
|
|
|
|
2015-08-05 07:26:59 -03:00
|
|
|
// Perform the writing and reading in a single command
|
|
|
|
if (PX4FLOW_REG == 0x00) {
|
2016-04-01 18:11:18 -03:00
|
|
|
if (!_dev->read_registers(0, val, I2C_FRAME_SIZE + I2C_INTEGRAL_FRAME_SIZE)) {
|
2015-11-02 11:19:13 -04:00
|
|
|
goto fail_transfer;
|
2015-08-05 07:26:59 -03:00
|
|
|
}
|
|
|
|
memcpy(&f_integral, &(val[I2C_FRAME_SIZE]), I2C_INTEGRAL_FRAME_SIZE);
|
|
|
|
}
|
2015-04-19 10:26:48 -03:00
|
|
|
|
2015-08-05 07:26:59 -03:00
|
|
|
if (PX4FLOW_REG == 0x16) {
|
2016-04-01 18:11:18 -03:00
|
|
|
if (!_dev->read_registers(0, val, I2C_INTEGRAL_FRAME_SIZE)) {
|
2015-11-02 11:19:13 -04:00
|
|
|
goto fail_transfer;
|
2015-08-05 07:26:59 -03:00
|
|
|
}
|
|
|
|
memcpy(&f_integral, val, I2C_INTEGRAL_FRAME_SIZE);
|
|
|
|
}
|
2015-04-19 10:26:48 -03:00
|
|
|
|
2016-04-01 18:11:18 -03:00
|
|
|
_dev->get_semaphore()->give();
|
2015-11-02 11:19:39 -04:00
|
|
|
|
|
|
|
// reduce error count
|
|
|
|
if (num_errors > 0) {
|
|
|
|
num_errors--;
|
|
|
|
}
|
|
|
|
|
2015-08-05 07:26:59 -03:00
|
|
|
report->pixel_flow_x_integral = static_cast<float>(f_integral.pixel_flow_x_integral) / 10000.0f; //convert to radians
|
|
|
|
report->pixel_flow_y_integral = static_cast<float>(f_integral.pixel_flow_y_integral) / 10000.0f; //convert to radians
|
|
|
|
report->frame_count_since_last_readout = f_integral.frame_count_since_last_readout;
|
|
|
|
report->ground_distance_m = static_cast<float>(f_integral.ground_distance) / 1000.0f; // convert to meters
|
|
|
|
report->quality = f_integral.qual; // 0:bad, 255 max quality
|
|
|
|
report->gyro_x_rate_integral = static_cast<float>(f_integral.gyro_x_rate_integral) / 10000.0f; // convert to radians
|
|
|
|
report->gyro_y_rate_integral = static_cast<float>(f_integral.gyro_y_rate_integral) / 10000.0f; // convert to radians
|
|
|
|
report->gyro_z_rate_integral = static_cast<float>(f_integral.gyro_z_rate_integral) / 10000.0f; // convert to radians
|
|
|
|
report->integration_timespan = f_integral.integration_timespan; // microseconds
|
|
|
|
report->time_since_last_sonar_update = f_integral.sonar_timestamp; // microseconds
|
|
|
|
report->gyro_temperature = f_integral.gyro_temperature; // Temperature * 100 in centi-degrees Celsius
|
|
|
|
report->sensor_id = 0;
|
2015-04-19 10:26:48 -03:00
|
|
|
|
2015-08-05 07:26:59 -03:00
|
|
|
return true;
|
2015-11-02 11:19:13 -04:00
|
|
|
|
|
|
|
fail_transfer:
|
|
|
|
num_errors++;
|
2016-04-01 18:11:18 -03:00
|
|
|
_dev->get_semaphore()->give();
|
2015-11-02 11:19:13 -04:00
|
|
|
return false;
|
2015-04-19 10:26:48 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
// update - read latest values from sensor and fill in x,y and totals.
|
|
|
|
void AP_OpticalFlow_Linux::update(void)
|
|
|
|
{
|
2015-08-05 07:26:59 -03:00
|
|
|
optical_flow_s report;
|
|
|
|
|
|
|
|
// return immediately if not initialised or more than half of last 40 reads have failed
|
|
|
|
if (!initialised || num_errors >= 20) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// throttle reads to no more than 10hz
|
2015-11-19 23:13:34 -04:00
|
|
|
uint32_t now = AP_HAL::millis();
|
2015-08-05 07:26:59 -03:00
|
|
|
if (now - last_read_ms < 100) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
last_read_ms = now;
|
|
|
|
|
2015-04-19 10:26:48 -03:00
|
|
|
// read the report from the sensor
|
2015-08-05 07:26:59 -03:00
|
|
|
if (!read(&report)) {
|
|
|
|
return;
|
|
|
|
}
|
2015-04-19 10:26:48 -03:00
|
|
|
|
|
|
|
// process
|
|
|
|
struct OpticalFlow::OpticalFlow_state state;
|
|
|
|
state.device_id = report.sensor_id;
|
|
|
|
state.surface_quality = report.quality;
|
|
|
|
if (report.integration_timespan > 0) {
|
|
|
|
const Vector2f flowScaler = _flowScaler();
|
|
|
|
float flowScaleFactorX = 1.0f + 0.001f * flowScaler.x;
|
|
|
|
float flowScaleFactorY = 1.0f + 0.001f * flowScaler.y;
|
|
|
|
float integralToRate = 1e6f / float(report.integration_timespan);
|
|
|
|
state.flowRate.x = flowScaleFactorX * integralToRate * float(report.pixel_flow_x_integral); // rad/sec measured optically about the X sensor axis
|
|
|
|
state.flowRate.y = flowScaleFactorY * integralToRate * float(report.pixel_flow_y_integral); // rad/sec measured optically about the Y sensor axis
|
|
|
|
state.bodyRate.x = integralToRate * float(report.gyro_x_rate_integral); // rad/sec measured inertially about the X sensor axis
|
|
|
|
state.bodyRate.y = integralToRate * float(report.gyro_y_rate_integral); // rad/sec measured inertially about the Y sensor axis
|
|
|
|
} else {
|
|
|
|
state.flowRate.zero();
|
|
|
|
state.bodyRate.zero();
|
|
|
|
}
|
|
|
|
|
2015-08-05 07:26:59 -03:00
|
|
|
// copy results to front end
|
2015-04-19 10:26:48 -03:00
|
|
|
_update_frontend(state);
|
|
|
|
|
2015-08-05 07:26:59 -03:00
|
|
|
#if PX4FLOW_DEBUG
|
2015-10-25 17:10:41 -03:00
|
|
|
hal.console->printf("PX4FLOW id:%u qual:%u FlowRateX:%4.2f Y:%4.2f BodyRateX:%4.2f y:%4.2f\n",
|
2015-08-05 07:26:59 -03:00
|
|
|
(unsigned)state.device_id,
|
|
|
|
(unsigned)state.surface_quality,
|
|
|
|
(double)state.flowRate.x,
|
|
|
|
(double)state.flowRate.y,
|
|
|
|
(double)state.bodyRate.x,
|
|
|
|
(double)state.bodyRate.y);
|
|
|
|
#endif
|
|
|
|
}
|
2015-04-19 10:26:48 -03:00
|
|
|
|
|
|
|
#endif // CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|