mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_RangeFinder: Added a new PX4 range finder and modified the RangeFinder parent class to support having multiple devices simultaneously
This commit is contained in:
parent
17eacf5bff
commit
18c06277f8
@ -8,3 +8,4 @@
|
||||
#include "AP_RangeFinder_MaxsonarI2CXL.h"
|
||||
#include "AP_RangeFinder_PulsedLightLRF.h"
|
||||
#include "AP_RangeFinder_analog.h"
|
||||
#include "AP_RangeFinder_PX4.h"
|
||||
|
132
libraries/AP_RangeFinder/AP_RangeFinder_PX4.cpp
Normal file
132
libraries/AP_RangeFinder/AP_RangeFinder_PX4.cpp
Normal file
@ -0,0 +1,132 @@
|
||||
// -*- 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_HAL.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
#include "AP_RangeFinder_PX4.h"
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <sys/stat.h>
|
||||
#include <fcntl.h>
|
||||
#include <unistd.h>
|
||||
|
||||
#include <drivers/drv_range_finder.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <stdio.h>
|
||||
#include <errno.h>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
// Constructor ////////////////////////////////////////////////////////
|
||||
AP_RangeFinder_PX4::AP_RangeFinder_PX4(FilterInt16 *filter) :
|
||||
RangeFinder(NULL, filter),
|
||||
_num_instances(0){ }
|
||||
|
||||
bool AP_RangeFinder_PX4::init(void)
|
||||
{
|
||||
_range_fd[0] = open(RANGE_FINDER_DEVICE_PATH, O_RDONLY);
|
||||
if (_range_fd[0] < 0) {
|
||||
hal.console->printf("Unable to open " RANGE_FINDER_DEVICE_PATH "\n");
|
||||
return false;
|
||||
}
|
||||
|
||||
_range_fd[1] = open(RANGE_FINDER_DEVICE_PATH "1", O_RDONLY);
|
||||
if (_range_fd[1] >= 0) {
|
||||
_num_instances = 2;
|
||||
} else {
|
||||
_num_instances = 1;
|
||||
}
|
||||
|
||||
for (uint8_t i=0; i<_num_instances; i++) {
|
||||
// average over up to 20 samples
|
||||
if (ioctl(_range_fd[i], SENSORIOCSQUEUEDEPTH, 20) != 0) {
|
||||
hal.console->printf("Failed to setup range finder queue\n");
|
||||
return false;
|
||||
}
|
||||
|
||||
_count[0] = 0;
|
||||
_sum[i] = 0;
|
||||
_healthy[i] = false;
|
||||
}
|
||||
|
||||
// give the driver a chance to run, and gather one sample
|
||||
hal.scheduler->delay(40);
|
||||
accumulate();
|
||||
if (_count[0] == 0) {
|
||||
hal.console->printf("Failed initial range finder accumulate\n");
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
bool AP_RangeFinder_PX4::take_reading(void)
|
||||
{
|
||||
// try to accumulate one more sample, so we have the latest data
|
||||
accumulate();
|
||||
|
||||
// consider the compass healthy if we got a reading in the last 0.2s
|
||||
for (uint8_t i=0; i<_num_instances; i++) {
|
||||
_healthy[i] = (hrt_absolute_time() - _last_timestamp[i] < 200000);
|
||||
}
|
||||
|
||||
for (uint8_t i=0; i<_num_instances; i++) {
|
||||
// avoid division by zero if we haven't received any range reports
|
||||
if (_count[i] == 0) continue;
|
||||
|
||||
_sum[i] /= _count[i];
|
||||
_sum[i] *= 100.00f;
|
||||
|
||||
_distance[i] = _mode_filter->apply(_sum[i]);
|
||||
|
||||
_sum[i] = 0;
|
||||
_count[i] = 0;
|
||||
}
|
||||
|
||||
return _healthy[_get_primary()];
|
||||
}
|
||||
|
||||
void AP_RangeFinder_PX4::accumulate(void)
|
||||
{
|
||||
struct range_finder_report range_report;
|
||||
for (uint8_t i=0; i<_num_instances; i++) {
|
||||
while (::read(_range_fd[i], &range_report, sizeof(range_report)) == sizeof(range_report) &&
|
||||
range_report.timestamp != _last_timestamp[i]) {
|
||||
|
||||
// Only take valid readings
|
||||
if (range_report.valid == 1) {
|
||||
_sum[i] += range_report.distance;
|
||||
_count[i]++;
|
||||
_last_timestamp[i] = range_report.timestamp;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
uint8_t AP_RangeFinder_PX4::_get_primary(void) const
|
||||
{
|
||||
for (uint8_t i=0; i<_num_instances; i++) {
|
||||
if (_healthy[i]) return i;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
int16_t AP_RangeFinder_PX4::read()
|
||||
{
|
||||
take_reading();
|
||||
return _distance[_get_primary()];
|
||||
}
|
||||
|
||||
#endif // CONFIG_HAL_BOARD
|
49
libraries/AP_RangeFinder/AP_RangeFinder_PX4.h
Normal file
49
libraries/AP_RangeFinder/AP_RangeFinder_PX4.h
Normal file
@ -0,0 +1,49 @@
|
||||
// -*- 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/>.
|
||||
*/
|
||||
|
||||
#ifndef AP_RangeFinder_PX4_H
|
||||
#define AP_RangeFinder_PX4_H
|
||||
|
||||
#include "RangeFinder.h"
|
||||
|
||||
class AP_RangeFinder_PX4 : public RangeFinder
|
||||
{
|
||||
public:
|
||||
// constructor
|
||||
AP_RangeFinder_PX4(FilterInt16 *filter);
|
||||
|
||||
// initialize all the range finder devices
|
||||
bool init(void);
|
||||
|
||||
bool take_reading(void);
|
||||
|
||||
void accumulate(void);
|
||||
|
||||
// read value from primary sensor and return distance in cm
|
||||
int16_t read();
|
||||
|
||||
// return the number of compass instances
|
||||
uint8_t get_count(void) const { return _num_instances; }
|
||||
private:
|
||||
uint8_t _get_primary(void) const;
|
||||
uint8_t _num_instances;
|
||||
int _range_fd[RANGEFINDER_MAX_INSTANCES];
|
||||
float _sum[RANGEFINDER_MAX_INSTANCES];
|
||||
uint32_t _count[RANGEFINDER_MAX_INSTANCES];
|
||||
uint64_t _last_timestamp[RANGEFINDER_MAX_INSTANCES];
|
||||
};
|
||||
|
||||
#endif // AP_RangeFinder_PX4_H
|
@ -18,6 +18,16 @@
|
||||
* #define AP_RANGEFINDER_ORIENTATION_FRONT_LEFT 5, 5, 0
|
||||
*/
|
||||
|
||||
/**
|
||||
maximum number of range finder instances available on this platform. If more
|
||||
than 1 then redundant sensors may be available
|
||||
*/
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
#define RANGEFINDER_MAX_INSTANCES 2
|
||||
#else
|
||||
#define RANGEFINDER_MAX_INSTANCES 1
|
||||
#endif
|
||||
|
||||
class RangeFinder
|
||||
{
|
||||
protected:
|
||||
@ -25,6 +35,10 @@ protected:
|
||||
_analog_source(source),
|
||||
_mode_filter(filter) {
|
||||
}
|
||||
|
||||
virtual uint8_t _get_primary(void) const { return 0; }
|
||||
bool _healthy[RANGEFINDER_MAX_INSTANCES];
|
||||
int16_t _distance[RANGEFINDER_MAX_INSTANCES]; // distance: in cm
|
||||
public:
|
||||
// distance: in cm
|
||||
int16_t distance;
|
||||
@ -49,5 +63,16 @@ public:
|
||||
|
||||
AP_HAL::AnalogSource* _analog_source;
|
||||
FilterInt16 * _mode_filter;
|
||||
|
||||
/// Return the number of range finder instances
|
||||
virtual uint8_t get_count(void) const { return 1; }
|
||||
|
||||
/// Return the current distance as a int16_t
|
||||
int16_t get_distance(uint8_t i) const { return _distance[i]; }
|
||||
int16_t get_distance(void) const { return get_distance(_get_primary()); }
|
||||
|
||||
/// Return the health of a range finder
|
||||
bool healthy(uint8_t i) const { return _healthy[i]; }
|
||||
bool healthy(void) const { return healthy(_get_primary()); }
|
||||
};
|
||||
#endif // __RANGEFINDER_H__
|
||||
|
Loading…
Reference in New Issue
Block a user