2014-06-09 14:14:50 -03: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/>.
|
|
|
|
*/
|
2016-02-17 21:25:44 -04:00
|
|
|
#pragma once
|
2012-01-10 19:44:04 -04:00
|
|
|
|
2015-08-11 03:28:45 -03:00
|
|
|
#include <AP_Common/AP_Common.h>
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#include <AP_Param/AP_Param.h>
|
2019-07-09 03:14:52 -03:00
|
|
|
#include <GCS_MAVLink/GCS.h>
|
2018-07-04 11:22:17 -03:00
|
|
|
#include "AP_RangeFinder_Params.h"
|
2012-01-10 19:44:04 -04:00
|
|
|
|
2014-06-09 14:14:50 -03:00
|
|
|
// Maximum number of range finder instances available on this platform
|
2019-10-19 01:13:36 -03:00
|
|
|
#ifndef RANGEFINDER_MAX_INSTANCES
|
2018-07-04 11:22:17 -03:00
|
|
|
#define RANGEFINDER_MAX_INSTANCES 10
|
2019-10-19 01:13:36 -03:00
|
|
|
#endif
|
|
|
|
|
2015-04-12 23:38:25 -03:00
|
|
|
#define RANGEFINDER_GROUND_CLEARANCE_CM_DEFAULT 10
|
2015-04-13 00:18:46 -03:00
|
|
|
#define RANGEFINDER_PREARM_ALT_MAX_CM 200
|
2018-10-02 20:43:50 -03:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
|
|
|
#define RANGEFINDER_PREARM_REQUIRED_CHANGE_CM 0
|
|
|
|
#else
|
2015-04-13 00:18:46 -03:00
|
|
|
#define RANGEFINDER_PREARM_REQUIRED_CHANGE_CM 50
|
2018-10-02 20:43:50 -03:00
|
|
|
#endif
|
2014-06-26 23:56:50 -03:00
|
|
|
|
2017-08-25 14:20:18 -03:00
|
|
|
class AP_RangeFinder_Backend;
|
|
|
|
|
2012-01-10 19:44:04 -04:00
|
|
|
class RangeFinder
|
|
|
|
{
|
2015-02-21 06:55:21 -04:00
|
|
|
friend class AP_RangeFinder_Backend;
|
2019-04-08 06:42:46 -03:00
|
|
|
//UAVCAN drivers are initialised in the Backend, hence list of drivers is needed there.
|
|
|
|
friend class AP_RangeFinder_UAVCAN;
|
2017-08-25 14:20:18 -03:00
|
|
|
public:
|
2019-07-09 03:14:52 -03:00
|
|
|
RangeFinder();
|
2017-08-25 14:20:18 -03:00
|
|
|
|
|
|
|
/* Do not allow copies */
|
|
|
|
RangeFinder(const RangeFinder &other) = delete;
|
|
|
|
RangeFinder &operator=(const RangeFinder&) = delete;
|
2014-06-09 14:14:50 -03:00
|
|
|
|
|
|
|
// RangeFinder driver types
|
|
|
|
enum RangeFinder_Type {
|
2014-06-26 23:56:50 -03:00
|
|
|
RangeFinder_TYPE_NONE = 0,
|
2014-07-16 10:52:46 -03:00
|
|
|
RangeFinder_TYPE_ANALOG = 1,
|
|
|
|
RangeFinder_TYPE_MBI2C = 2,
|
|
|
|
RangeFinder_TYPE_PLI2C = 3,
|
2015-02-21 06:55:21 -04:00
|
|
|
RangeFinder_TYPE_PX4 = 4,
|
2015-07-06 16:24:06 -03:00
|
|
|
RangeFinder_TYPE_PX4_PWM= 5,
|
2015-08-28 06:52:34 -03:00
|
|
|
RangeFinder_TYPE_BBB_PRU= 6,
|
2015-09-07 02:32:06 -03:00
|
|
|
RangeFinder_TYPE_LWI2C = 7,
|
2016-04-15 14:31:51 -03:00
|
|
|
RangeFinder_TYPE_LWSER = 8,
|
2016-05-04 00:02:44 -03:00
|
|
|
RangeFinder_TYPE_BEBOP = 9,
|
2016-09-13 00:24:41 -03:00
|
|
|
RangeFinder_TYPE_MAVLink = 10,
|
2016-11-14 17:47:45 -04:00
|
|
|
RangeFinder_TYPE_ULANDING= 11,
|
2016-04-19 18:32:17 -03:00
|
|
|
RangeFinder_TYPE_LEDDARONE = 12,
|
2016-12-15 20:53:30 -04:00
|
|
|
RangeFinder_TYPE_MBSER = 13,
|
2017-07-28 09:46:52 -03:00
|
|
|
RangeFinder_TYPE_TRI2C = 14,
|
2017-03-01 00:22:32 -04:00
|
|
|
RangeFinder_TYPE_PLI2CV3= 15,
|
2018-05-14 02:03:08 -03:00
|
|
|
RangeFinder_TYPE_VL53L0X = 16,
|
2018-05-16 19:31:22 -03:00
|
|
|
RangeFinder_TYPE_NMEA = 17,
|
|
|
|
RangeFinder_TYPE_WASP = 18,
|
2018-05-25 22:59:36 -03:00
|
|
|
RangeFinder_TYPE_BenewakeTF02 = 19,
|
2018-07-27 07:22:26 -03:00
|
|
|
RangeFinder_TYPE_BenewakeTFmini = 20,
|
|
|
|
RangeFinder_TYPE_PLI2CV3HP = 21,
|
2018-08-29 11:18:49 -03:00
|
|
|
RangeFinder_TYPE_PWM = 22,
|
2019-03-28 09:43:23 -03:00
|
|
|
RangeFinder_TYPE_BLPing = 23,
|
2019-04-26 04:23:45 -03:00
|
|
|
RangeFinder_TYPE_UAVCAN = 24,
|
|
|
|
RangeFinder_TYPE_BenewakeTFminiPlus = 25,
|
2019-08-31 08:21:01 -03:00
|
|
|
RangeFinder_TYPE_Lanbao = 26,
|
2019-10-14 06:30:48 -03:00
|
|
|
RangeFinder_TYPE_BenewakeTF03 = 27,
|
2014-06-09 14:14:50 -03:00
|
|
|
};
|
|
|
|
|
2014-06-26 23:56:50 -03:00
|
|
|
enum RangeFinder_Function {
|
|
|
|
FUNCTION_LINEAR = 0,
|
|
|
|
FUNCTION_INVERTED = 1,
|
|
|
|
FUNCTION_HYPERBOLA = 2
|
2014-06-09 14:14:50 -03:00
|
|
|
};
|
2014-06-26 23:56:50 -03:00
|
|
|
|
2015-04-13 03:03:19 -03:00
|
|
|
enum RangeFinder_Status {
|
|
|
|
RangeFinder_NotConnected = 0,
|
|
|
|
RangeFinder_NoData,
|
|
|
|
RangeFinder_OutOfRangeLow,
|
|
|
|
RangeFinder_OutOfRangeHigh,
|
|
|
|
RangeFinder_Good
|
|
|
|
};
|
2014-06-26 23:56:50 -03:00
|
|
|
|
2014-06-09 14:14:50 -03:00
|
|
|
// The RangeFinder_State structure is filled in by the backend driver
|
|
|
|
struct RangeFinder_State {
|
2018-08-27 03:04:32 -03:00
|
|
|
uint16_t distance_cm; // distance: in cm
|
|
|
|
uint16_t voltage_mv; // voltage in millivolts, if applicable, otherwise 0
|
|
|
|
enum RangeFinder_Status status; // sensor status
|
|
|
|
uint8_t range_valid_count; // number of consecutive valid readings (maxes out at 10)
|
AP_RangeFinder: support last_reading_ms
Benewake, LeddarOne, LightWareSerial, MAVLink, MaxsonarI2CXL, MaxsonarSerialLV, NMEA, PX4_PWM, uLanding and Wasp already stored the last read time so for these drivers, this change just moves that storage to the state structure
analog, BBB_PRU, Bebop, LightWareI2C, PulsedLightLRF, TeraRangerI2C, VL53L0X did not store the last read time so this was added
2018-08-27 04:02:51 -03:00
|
|
|
uint32_t last_reading_ms; // system time of last successful update from sensor
|
2017-08-07 00:04:56 -03:00
|
|
|
|
2018-05-16 20:05:50 -03:00
|
|
|
const struct AP_Param::GroupInfo *var_info;
|
2014-06-09 14:14:50 -03:00
|
|
|
};
|
2012-01-10 19:44:04 -04:00
|
|
|
|
2018-05-16 20:05:50 -03:00
|
|
|
static const struct AP_Param::GroupInfo *backend_var_info[RANGEFINDER_MAX_INSTANCES];
|
2014-06-26 23:56:50 -03:00
|
|
|
|
2017-08-07 00:04:56 -03:00
|
|
|
// parameters for each instance
|
2014-06-09 14:14:50 -03:00
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
2019-04-05 06:20:22 -03:00
|
|
|
|
|
|
|
void set_log_rfnd_bit(uint32_t log_rfnd_bit) { _log_rfnd_bit = log_rfnd_bit; }
|
|
|
|
|
2014-06-09 14:14:50 -03:00
|
|
|
// Return the number of range finder instances
|
|
|
|
uint8_t num_sensors(void) const {
|
|
|
|
return num_instances;
|
2012-11-27 21:39:15 -04:00
|
|
|
}
|
2012-01-10 19:44:04 -04:00
|
|
|
|
2019-04-10 04:32:15 -03:00
|
|
|
// prearm checks
|
|
|
|
bool prearm_healthy(char *failure_msg, const uint8_t failure_msg_len) const;
|
|
|
|
|
2014-06-26 23:56:50 -03:00
|
|
|
// detect and initialise any available rangefinders
|
2019-04-05 06:13:42 -03:00
|
|
|
void init(enum Rotation orientation_default);
|
2014-06-26 23:56:50 -03:00
|
|
|
|
|
|
|
// update state of all rangefinders. Should be called at around
|
|
|
|
// 10Hz from main loop
|
2014-06-09 14:14:50 -03:00
|
|
|
void update(void);
|
2016-05-04 00:02:44 -03:00
|
|
|
|
2016-05-03 23:55:05 -03:00
|
|
|
// Handle an incoming DISTANCE_SENSOR message (from a MAVLink enabled range finder)
|
2019-04-30 07:22:49 -03:00
|
|
|
void handle_msg(const mavlink_message_t &msg);
|
2016-05-04 00:02:44 -03:00
|
|
|
|
2017-02-09 06:26:57 -04:00
|
|
|
// return true if we have a range finder with the specified orientation
|
|
|
|
bool has_orientation(enum Rotation orientation) const;
|
|
|
|
|
|
|
|
// find first range finder instance with the specified orientation
|
2017-08-08 02:54:09 -03:00
|
|
|
AP_RangeFinder_Backend *find_instance(enum Rotation orientation) const;
|
2017-02-09 06:26:57 -04:00
|
|
|
|
2017-08-08 02:54:09 -03:00
|
|
|
AP_RangeFinder_Backend *get_backend(uint8_t id) const;
|
2017-02-09 06:26:57 -04:00
|
|
|
|
2017-08-08 02:54:09 -03:00
|
|
|
// methods to return a distance on a particular orientation from
|
|
|
|
// any sensor which can current supply it
|
2017-02-09 06:26:57 -04:00
|
|
|
uint16_t distance_cm_orient(enum Rotation orientation) const;
|
|
|
|
uint16_t voltage_mv_orient(enum Rotation orientation) const;
|
|
|
|
int16_t max_distance_cm_orient(enum Rotation orientation) const;
|
|
|
|
int16_t min_distance_cm_orient(enum Rotation orientation) const;
|
|
|
|
int16_t ground_clearance_cm_orient(enum Rotation orientation) const;
|
2017-08-08 04:32:53 -03:00
|
|
|
MAV_DISTANCE_SENSOR get_mav_distance_sensor_type_orient(enum Rotation orientation) const;
|
2017-02-09 06:26:57 -04:00
|
|
|
RangeFinder_Status status_orient(enum Rotation orientation) const;
|
|
|
|
bool has_data_orient(enum Rotation orientation) const;
|
|
|
|
uint8_t range_valid_count_orient(enum Rotation orientation) const;
|
2017-08-08 02:54:09 -03:00
|
|
|
const Vector3f &get_pos_offset_orient(enum Rotation orientation) const;
|
AP_RangeFinder: support last_reading_ms
Benewake, LeddarOne, LightWareSerial, MAVLink, MaxsonarI2CXL, MaxsonarSerialLV, NMEA, PX4_PWM, uLanding and Wasp already stored the last read time so for these drivers, this change just moves that storage to the state structure
analog, BBB_PRU, Bebop, LightWareI2C, PulsedLightLRF, TeraRangerI2C, VL53L0X did not store the last read time so this was added
2018-08-27 04:02:51 -03:00
|
|
|
uint32_t last_reading_ms(enum Rotation orientation) const;
|
2015-02-21 06:55:21 -04:00
|
|
|
|
2019-04-05 06:20:22 -03:00
|
|
|
// indicate which bit in LOG_BITMASK indicates RFND should be logged
|
|
|
|
void set_rfnd_bit(uint32_t log_rfnd_bit) { _log_rfnd_bit = log_rfnd_bit; }
|
|
|
|
|
2015-02-21 06:55:21 -04:00
|
|
|
/*
|
|
|
|
set an externally estimated terrain height. Used to enable power
|
|
|
|
saving (where available) at high altitudes.
|
|
|
|
*/
|
|
|
|
void set_estimated_terrain_height(float height) {
|
|
|
|
estimated_terrain_height = height;
|
|
|
|
}
|
2015-04-13 00:18:46 -03:00
|
|
|
|
2018-05-09 04:45:26 -03:00
|
|
|
static RangeFinder *get_singleton(void) { return _singleton; }
|
|
|
|
|
2018-07-04 11:22:17 -03:00
|
|
|
protected:
|
|
|
|
AP_RangeFinder_Params params[RANGEFINDER_MAX_INSTANCES];
|
2016-10-07 19:29:42 -03:00
|
|
|
|
2014-06-09 14:14:50 -03:00
|
|
|
private:
|
2018-05-09 04:45:26 -03:00
|
|
|
static RangeFinder *_singleton;
|
|
|
|
|
2014-06-09 14:14:50 -03:00
|
|
|
RangeFinder_State state[RANGEFINDER_MAX_INSTANCES];
|
|
|
|
AP_RangeFinder_Backend *drivers[RANGEFINDER_MAX_INSTANCES];
|
2019-02-03 21:30:05 -04:00
|
|
|
uint8_t num_instances;
|
2015-02-21 06:55:21 -04:00
|
|
|
float estimated_terrain_height;
|
2017-02-09 06:26:57 -04:00
|
|
|
Vector3f pos_offset_zero; // allows returning position offsets of zero for invalid requests
|
2014-06-09 14:14:50 -03:00
|
|
|
|
2018-07-04 11:22:17 -03:00
|
|
|
void convert_params(void);
|
|
|
|
|
2018-02-23 08:11:47 -04:00
|
|
|
void detect_instance(uint8_t instance, uint8_t& serial_instance);
|
2015-04-13 00:18:46 -03:00
|
|
|
|
2016-11-11 17:58:46 -04:00
|
|
|
bool _add_backend(AP_RangeFinder_Backend *driver);
|
2019-04-05 06:20:22 -03:00
|
|
|
|
|
|
|
uint32_t _log_rfnd_bit = -1;
|
|
|
|
void Log_RFND();
|
|
|
|
};
|
|
|
|
|
|
|
|
namespace AP {
|
|
|
|
RangeFinder *rangefinder();
|
2012-01-10 19:44:04 -04:00
|
|
|
};
|