AP_Rangefinder: rename trone to TeraRangerI2C
This commit is contained in:
parent
b6076bcb77
commit
0993300506
@ -13,9 +13,9 @@
|
||||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
/*
|
||||
driver for trone rangefinder
|
||||
driver for TeraRanger I2C rangefinders
|
||||
*/
|
||||
#include "AP_RangeFinder_trone.h"
|
||||
#include "AP_RangeFinder_TeraRangerI2C.h"
|
||||
|
||||
#include <utility>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
@ -26,30 +26,30 @@ extern const AP_HAL::HAL& hal;
|
||||
#define TRONE_I2C_ADDR 0x30
|
||||
|
||||
// registers
|
||||
#define TRONE_MEASURE 0x00
|
||||
#define TRONE_WHOAMI 0x01
|
||||
#define TRONE_WHOAMI_VALUE 0xA1
|
||||
#define TR_MEASURE 0x00
|
||||
#define TR_WHOAMI 0x01
|
||||
#define TR_WHOAMI_VALUE 0xA1
|
||||
|
||||
/*
|
||||
The constructor also initializes 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_trone::AP_RangeFinder_trone(uint8_t bus, RangeFinder::RangeFinder_State &_state)
|
||||
AP_RangeFinder_TeraRangerI2C::AP_RangeFinder_TeraRangerI2C(uint8_t bus, RangeFinder::RangeFinder_State &_state)
|
||||
: AP_RangeFinder_Backend(_state)
|
||||
, dev(hal.i2c_mgr->get_device(bus, TRONE_I2C_ADDR))
|
||||
{
|
||||
}
|
||||
|
||||
/*
|
||||
detect if a trone rangefinder is connected. We'll detect by
|
||||
detect if a TeraRanger rangefinder is connected. We'll detect by
|
||||
trying to take a reading on I2C. If we get a result the sensor is
|
||||
there.
|
||||
*/
|
||||
AP_RangeFinder_Backend *AP_RangeFinder_trone::detect(uint8_t bus,
|
||||
RangeFinder::RangeFinder_State &_state)
|
||||
AP_RangeFinder_Backend *AP_RangeFinder_TeraRangerI2C::detect(uint8_t bus,
|
||||
RangeFinder::RangeFinder_State &_state)
|
||||
{
|
||||
AP_RangeFinder_trone *sensor = new AP_RangeFinder_trone(bus, _state);
|
||||
AP_RangeFinder_TeraRangerI2C *sensor = new AP_RangeFinder_TeraRangerI2C(bus, _state);
|
||||
if (!sensor) {
|
||||
return nullptr;
|
||||
}
|
||||
@ -65,7 +65,7 @@ AP_RangeFinder_Backend *AP_RangeFinder_trone::detect(uint8_t bus,
|
||||
/*
|
||||
initialise sensor
|
||||
*/
|
||||
bool AP_RangeFinder_trone::init(void)
|
||||
bool AP_RangeFinder_TeraRangerI2C::init(void)
|
||||
{
|
||||
if (!dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
||||
return false;
|
||||
@ -75,8 +75,8 @@ bool AP_RangeFinder_trone::init(void)
|
||||
|
||||
// check WHOAMI
|
||||
uint8_t whoami;
|
||||
if (!dev->read_registers(TRONE_WHOAMI, &whoami, 1) ||
|
||||
whoami != TRONE_WHOAMI_VALUE) {
|
||||
if (!dev->read_registers(TR_WHOAMI, &whoami, 1) ||
|
||||
whoami != TR_WHOAMI_VALUE) {
|
||||
return false;
|
||||
}
|
||||
|
||||
@ -99,20 +99,20 @@ bool AP_RangeFinder_trone::init(void)
|
||||
dev->set_retries(1);
|
||||
|
||||
dev->register_periodic_callback(50000,
|
||||
FUNCTOR_BIND_MEMBER(&AP_RangeFinder_trone::timer, void));
|
||||
FUNCTOR_BIND_MEMBER(&AP_RangeFinder_TeraRangerI2C::timer, void));
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
// measure() - ask sensor to make a range reading
|
||||
bool AP_RangeFinder_trone::measure()
|
||||
bool AP_RangeFinder_TeraRangerI2C::measure()
|
||||
{
|
||||
uint8_t cmd = TRONE_MEASURE;
|
||||
uint8_t cmd = TR_MEASURE;
|
||||
return dev->transfer(&cmd, 1, nullptr, 0);
|
||||
}
|
||||
|
||||
// collect - return last value measured by sensor
|
||||
bool AP_RangeFinder_trone::collect(uint16_t &_distance_cm)
|
||||
bool AP_RangeFinder_TeraRangerI2C::collect(uint16_t &_distance_cm)
|
||||
{
|
||||
uint8_t d[3];
|
||||
|
||||
@ -134,7 +134,7 @@ bool AP_RangeFinder_trone::collect(uint16_t &_distance_cm)
|
||||
/*
|
||||
timer called at 20Hz
|
||||
*/
|
||||
void AP_RangeFinder_trone::timer(void)
|
||||
void AP_RangeFinder_TeraRangerI2C::timer(void)
|
||||
{
|
||||
// take a reading
|
||||
uint16_t _distance_cm;
|
||||
@ -152,7 +152,7 @@ void AP_RangeFinder_trone::timer(void)
|
||||
/*
|
||||
update the state of the sensor
|
||||
*/
|
||||
void AP_RangeFinder_trone::update(void)
|
||||
void AP_RangeFinder_TeraRangerI2C::update(void)
|
||||
{
|
||||
if (_sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
||||
if (accum.count > 0) {
|
@ -4,7 +4,7 @@
|
||||
#include "RangeFinder_Backend.h"
|
||||
#include <AP_HAL/I2CDevice.h>
|
||||
|
||||
class AP_RangeFinder_trone : public AP_RangeFinder_Backend
|
||||
class AP_RangeFinder_TeraRangerI2C : public AP_RangeFinder_Backend
|
||||
{
|
||||
public:
|
||||
// static detection function
|
||||
@ -22,7 +22,7 @@ protected:
|
||||
|
||||
private:
|
||||
// constructor
|
||||
AP_RangeFinder_trone(uint8_t bus, RangeFinder::RangeFinder_State &_state);
|
||||
AP_RangeFinder_TeraRangerI2C(uint8_t bus, RangeFinder::RangeFinder_State &_state);
|
||||
|
||||
bool measure(void);
|
||||
bool collect(uint16_t &distance_cm);
|
@ -26,7 +26,7 @@
|
||||
#include "AP_RangeFinder_MAVLink.h"
|
||||
#include "AP_RangeFinder_LeddarOne.h"
|
||||
#include "AP_RangeFinder_uLanding.h"
|
||||
#include "AP_RangeFinder_trone.h"
|
||||
#include "AP_RangeFinder_TeraRangerI2C.h"
|
||||
#include "AP_RangeFinder_VL53L0X.h"
|
||||
#include <AP_BoardConfig/AP_BoardConfig.h>
|
||||
|
||||
@ -37,7 +37,7 @@ const AP_Param::GroupInfo RangeFinder::var_info[] = {
|
||||
// @Param: _TYPE
|
||||
// @DisplayName: Rangefinder type
|
||||
// @Description: What type of rangefinder device that is connected
|
||||
// @Values: 0:None,1:Analog,2:MaxbotixI2C,3:LidarLiteV2-I2C,5:PX4-PWM,6:BBB-PRU,7:LightWareI2C,8:LightWareSerial,9:Bebop,10:MAVLink,11:uLanding,12:LeddarOne,13:MaxbotixSerial,14:TrOneI2C,15:LidarLiteV3-I2C,16:VL53L0X
|
||||
// @Values: 0:None,1:Analog,2:MaxbotixI2C,3:LidarLiteV2-I2C,5:PX4-PWM,6:BBB-PRU,7:LightWareI2C,8:LightWareSerial,9:Bebop,10:MAVLink,11:uLanding,12:LeddarOne,13:MaxbotixSerial,14:TeraRangerI2C,15:LidarLiteV3-I2C,16:VL53L0X
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("_TYPE", 0, RangeFinder, state[0].type, 0),
|
||||
|
||||
@ -164,7 +164,7 @@ const AP_Param::GroupInfo RangeFinder::var_info[] = {
|
||||
// @Param: 2_TYPE
|
||||
// @DisplayName: Second Rangefinder type
|
||||
// @Description: What type of rangefinder device that is connected
|
||||
// @Values: 0:None,1:Analog,2:MaxbotixI2C,3:LidarLiteV2-I2C,5:PX4-PWM,6:BBB-PRU,7:LightWareI2C,8:LightWareSerial,9:Bebop,10:MAVLink,11:uLanding,12:LeddarOne,13:MaxbotixSerial,14:TrOneI2C,15:LidarLiteV3-I2C,16:VL53L0X
|
||||
// @Values: 0:None,1:Analog,2:MaxbotixI2C,3:LidarLiteV2-I2C,5:PX4-PWM,6:BBB-PRU,7:LightWareI2C,8:LightWareSerial,9:Bebop,10:MAVLink,11:uLanding,12:LeddarOne,13:MaxbotixSerial,14:TeraRangerI2C,15:LidarLiteV3-I2C,16:VL53L0X
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("2_TYPE", 12, RangeFinder, state[1].type, 0),
|
||||
|
||||
@ -285,7 +285,7 @@ const AP_Param::GroupInfo RangeFinder::var_info[] = {
|
||||
// @Param: 3_TYPE
|
||||
// @DisplayName: Third Rangefinder type
|
||||
// @Description: What type of rangefinder device that is connected
|
||||
// @Values: 0:None,1:Analog,2:MaxbotixI2C,3:LidarLiteV2-I2C,5:PX4-PWM,6:BBB-PRU,7:LightWareI2C,8:LightWareSerial,9:Bebop,10:MAVLink,11:uLanding,12:LeddarOne,13:MaxbotixSerial,14:TrOneI2C,15:LidarLiteV3-I2C,16:VL53L0X
|
||||
// @Values: 0:None,1:Analog,2:MaxbotixI2C,3:LidarLiteV2-I2C,5:PX4-PWM,6:BBB-PRU,7:LightWareI2C,8:LightWareSerial,9:Bebop,10:MAVLink,11:uLanding,12:LeddarOne,13:MaxbotixSerial,14:TeraRangerI2C,15:LidarLiteV3-I2C,16:VL53L0X
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("3_TYPE", 25, RangeFinder, state[2].type, 0),
|
||||
|
||||
@ -406,7 +406,7 @@ const AP_Param::GroupInfo RangeFinder::var_info[] = {
|
||||
// @Param: 4_TYPE
|
||||
// @DisplayName: Fourth Rangefinder type
|
||||
// @Description: What type of rangefinder device that is connected
|
||||
// @Values: 0:None,1:Analog,2:MaxbotixI2C,3:LidarLiteV2-I2C,5:PX4-PWM,6:BBB-PRU,7:LightWareI2C,8:LightWareSerial,9:Bebop,10:MAVLink,11:uLanding,12:LeddarOne,13:MaxbotixSerial,14:TrOneI2C,15:LidarLiteV3-I2C,16:VL53L0X
|
||||
// @Values: 0:None,1:Analog,2:MaxbotixI2C,3:LidarLiteV2-I2C,5:PX4-PWM,6:BBB-PRU,7:LightWareI2C,8:LightWareSerial,9:Bebop,10:MAVLink,11:uLanding,12:LeddarOne,13:MaxbotixSerial,14:TeraRangerI2C,15:LidarLiteV3-I2C,16:VL53L0X
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("4_TYPE", 37, RangeFinder, state[3].type, 0),
|
||||
|
||||
@ -622,9 +622,9 @@ void RangeFinder::detect_instance(uint8_t instance)
|
||||
hal.i2c_mgr->get_device(HAL_RANGEFINDER_LIGHTWARE_I2C_BUS, state[instance].address)));
|
||||
}
|
||||
break;
|
||||
case RangeFinder_TYPE_TRONE:
|
||||
if (!_add_backend(AP_RangeFinder_trone::detect(0, state[instance]))) {
|
||||
_add_backend(AP_RangeFinder_trone::detect(1, state[instance]));
|
||||
case RangeFinder_TYPE_TRI2C:
|
||||
if (!_add_backend(AP_RangeFinder_TeraRangerI2C::detect(0, state[instance]))) {
|
||||
_add_backend(AP_RangeFinder_TeraRangerI2C::detect(1, state[instance]));
|
||||
}
|
||||
break;
|
||||
case RangeFinder_TYPE_VL53L0X:
|
||||
|
@ -51,7 +51,7 @@ public:
|
||||
RangeFinder_TYPE_ULANDING= 11,
|
||||
RangeFinder_TYPE_LEDDARONE = 12,
|
||||
RangeFinder_TYPE_MBSER = 13,
|
||||
RangeFinder_TYPE_TRONE = 14,
|
||||
RangeFinder_TYPE_TRI2C = 14,
|
||||
RangeFinder_TYPE_PLI2CV3= 15,
|
||||
RangeFinder_TYPE_VL53L0X = 16
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user