Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

RangeFinder: refactoring parameter management #8816

Closed
wants to merge 18 commits into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
18 commits
Select commit Hold shift + click to select a range
882c828
RangeFinder: changed the way settings are handled so that up to 7 ran…
256shadesofgrey Jul 4, 2018
266146a
RangeFinder: Fixed errors related to bbbmini
256shadesofgrey Jul 6, 2018
20d2d01
RangeFinder: Removed commented-out code.
256shadesofgrey Jul 6, 2018
8cdcbe0
RangeFinder: another fix related to px4-v4pro
256shadesofgrey Jul 6, 2018
0f42a0e
RangeFinder: Removed the 3 bit limitation for the enumeration of rang…
256shadesofgrey Jul 20, 2018
fff3ed5
RangeFinder: Up to 10 range finders can now be used at once.
256shadesofgrey Jul 20, 2018
c45afd9
RangeFinder: Added parameter conversion function.
256shadesofgrey Aug 1, 2018
4872707
RangeFinder: fixed conversionTable[].
256shadesofgrey Aug 2, 2018
53256e9
RangeFinder: removed commented-out code
256shadesofgrey Aug 2, 2018
0bddeb6
RangeFinder: changed backend parameter indexes to old values to simpl…
256shadesofgrey Aug 3, 2018
f0a1551
RangeFinder: Resolved minor issues caused by changes made with the as…
256shadesofgrey Oct 2, 2018
2e98e49
RangeFinder: resolved conflicts caused by drivers for new sensors.
256shadesofgrey Jan 10, 2019
a076649
Autotest: renamed requested RangeFinder parameters to account for the…
256shadesofgrey Jan 14, 2019
79e2f56
RangeFinder: changed parameter indexes so that 0 isn't used.
256shadesofgrey Jan 22, 2019
b666d63
RangeFinder: fixed formatting and a typo.
256shadesofgrey Jan 24, 2019
0063679
RangeFinder: fixed an issue that caused the RNGFNDX_PWRRNG parameter …
256shadesofgrey Jan 24, 2019
a3f05e8
RangeFinder: fixed an issue with the conversion of long parameters.
256shadesofgrey Jan 29, 2019
0f5784f
RangeFinder: fixed an issue with the conversion of long parameters. H…
256shadesofgrey Jan 29, 2019
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
60 changes: 30 additions & 30 deletions Tools/autotest/arducopter.py
Expand Up @@ -389,11 +389,11 @@ def fly_loiter_to_alt(self):
self.fetch_parameters()
self.set_parameter("PLND_TYPE", 4)

self.set_parameter("RNGFND_TYPE", 1)
self.set_parameter("RNGFND_MIN_CM", 0)
self.set_parameter("RNGFND_MAX_CM", 4000)
self.set_parameter("RNGFND_PIN", 0)
self.set_parameter("RNGFND_SCALING", 12.12)
self.set_parameter("RNGFND1_TYPE", 1)
self.set_parameter("RNGFND1_MIN_CM", 0)
self.set_parameter("RNGFND1_MAX_CM", 4000)
self.set_parameter("RNGFND1_PIN", 0)
self.set_parameter("RNGFND1_SCALING", 12.12)

self.reboot_sitl()

Expand Down Expand Up @@ -1030,11 +1030,11 @@ def fly_optical_flow_limits(self):
self.set_parameter("SIM_FLOW_ENABLE", 1)
self.set_parameter("FLOW_ENABLE", 1)

self.set_parameter("RNGFND_TYPE", 1)
self.set_parameter("RNGFND_MIN_CM", 0)
self.set_parameter("RNGFND_MAX_CM", 4000)
self.set_parameter("RNGFND_PIN", 0)
self.set_parameter("RNGFND_SCALING", 12.12, epsilon=0.01)
self.set_parameter("RNGFND1_TYPE", 1)
self.set_parameter("RNGFND1_MIN_CM", 0)
self.set_parameter("RNGFND1_MAX_CM", 4000)
self.set_parameter("RNGFND1_PIN", 0)
self.set_parameter("RNGFND1_SCALING", 12.12, epsilon=0.01)

self.set_parameter("SIM_GPS_DISABLE", 1)
self.set_parameter("SIM_TERRAIN", 0)
Expand Down Expand Up @@ -1461,11 +1461,11 @@ def test_rangefinder(self):
raise NotAchievedException("Received unexpected RANGEFINDER msg")

try:
self.set_parameter("RNGFND_TYPE", 1)
self.set_parameter("RNGFND_MIN_CM", 0)
self.set_parameter("RNGFND_MAX_CM", 4000)
self.set_parameter("RNGFND_PIN", 0)
self.set_parameter("RNGFND_SCALING", 12.12)
self.set_parameter("RNGFND1_TYPE", 1)
self.set_parameter("RNGFND1_MIN_CM", 0)
self.set_parameter("RNGFND1_MAX_CM", 4000)
self.set_parameter("RNGFND1_PIN", 0)
self.set_parameter("RNGFND1_SCALING", 12.12)
self.set_parameter("RC9_OPTION", 10) # rangefinder
self.set_rc(9, 2000)

Expand Down Expand Up @@ -1586,11 +1586,11 @@ def fly_precision_sitl(self):
self.fetch_parameters()
self.set_parameter("PLND_TYPE", 4)

self.set_parameter("RNGFND_TYPE", 1)
self.set_parameter("RNGFND_MIN_CM", 0)
self.set_parameter("RNGFND_MAX_CM", 4000)
self.set_parameter("RNGFND_PIN", 0)
self.set_parameter("RNGFND_SCALING", 12.12)
self.set_parameter("RNGFND1_TYPE", 1)
self.set_parameter("RNGFND1_MIN_CM", 0)
self.set_parameter("RNGFND1_MAX_CM", 4000)
self.set_parameter("RNGFND1_PIN", 0)
self.set_parameter("RNGFND1_SCALING", 12.12)

self.reboot_sitl()

Expand Down Expand Up @@ -2038,11 +2038,11 @@ def fly_payload_place_mission(self):

ex = None
try:
self.set_parameter("RNGFND_TYPE", 1)
self.set_parameter("RNGFND_MIN_CM", 0)
self.set_parameter("RNGFND_MAX_CM", 4000)
self.set_parameter("RNGFND_PIN", 0)
self.set_parameter("RNGFND_SCALING", 12.12)
self.set_parameter("RNGFND1_TYPE", 1)
self.set_parameter("RNGFND1_MIN_CM", 0)
self.set_parameter("RNGFND1_MAX_CM", 4000)
self.set_parameter("RNGFND1_PIN", 0)
self.set_parameter("RNGFND1_SCALING", 12.12)
self.set_parameter("GRIP_ENABLE", 1)
self.set_parameter("GRIP_TYPE", 1)
self.set_parameter("SIM_GRPS_ENABLE", 1)
Expand Down Expand Up @@ -2483,11 +2483,11 @@ def fly_precision_companion(self):
# enable companion backend:
self.set_parameter("PLND_TYPE", 1)

self.set_parameter("RNGFND_TYPE", 1)
self.set_parameter("RNGFND_MIN_CM", 0)
self.set_parameter("RNGFND_MAX_CM", 4000)
self.set_parameter("RNGFND_PIN", 0)
self.set_parameter("RNGFND_SCALING", 12.12)
self.set_parameter("RNGFND1_TYPE", 1)
self.set_parameter("RNGFND1_MIN_CM", 0)
self.set_parameter("RNGFND1_MAX_CM", 4000)
self.set_parameter("RNGFND1_PIN", 0)
self.set_parameter("RNGFND1_SCALING", 12.12)

# set up a channel switch to enable precision loiter:
self.set_parameter("RC7_OPTION", 39)
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_Proximity/AP_Proximity.h
Expand Up @@ -147,8 +147,8 @@ class AP_Proximity
Proximity_State state[PROXIMITY_MAX_INSTANCES];
AP_Proximity_Backend *drivers[PROXIMITY_MAX_INSTANCES];
const RangeFinder *_rangefinder;
uint8_t primary_instance:3;
uint8_t num_instances:3;
uint8_t primary_instance;
uint8_t num_instances;
AP_SerialManager &serial_manager;

// parameters for all instances
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_RangeFinder/AP_RangeFinder_BBB_PRU.cpp
Expand Up @@ -39,8 +39,8 @@ volatile struct range *rangerpru;
constructor is not called until detect() returns true, so we
already know that we should setup the rangefinder
*/
AP_RangeFinder_BBB_PRU::AP_RangeFinder_BBB_PRU(RangeFinder::RangeFinder_State &_state) :
AP_RangeFinder_Backend(_state)
AP_RangeFinder_BBB_PRU::AP_RangeFinder_BBB_PRU(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) :
AP_RangeFinder_Backend(_state, _params)
{
}

Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_RangeFinder/AP_RangeFinder_BBB_PRU.h
Expand Up @@ -21,7 +21,7 @@ class AP_RangeFinder_BBB_PRU : public AP_RangeFinder_Backend
{
public:
// constructor
AP_RangeFinder_BBB_PRU(RangeFinder::RangeFinder_State &_state);
AP_RangeFinder_BBB_PRU(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params);

// static detection function
static bool detect();
Expand Down
3 changes: 2 additions & 1 deletion libraries/AP_RangeFinder/AP_RangeFinder_Benewake.cpp
Expand Up @@ -49,10 +49,11 @@ extern const AP_HAL::HAL& hal;
already know that we should setup the rangefinder
*/
AP_RangeFinder_Benewake::AP_RangeFinder_Benewake(RangeFinder::RangeFinder_State &_state,
AP_RangeFinder_Params &_params,
AP_SerialManager &serial_manager,
uint8_t serial_instance,
benewake_model_type model) :
AP_RangeFinder_Backend(_state),
AP_RangeFinder_Backend(_state, _params),
model_type(model)
{
uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance);
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_RangeFinder/AP_RangeFinder_Benewake.h
Expand Up @@ -15,6 +15,7 @@ class AP_RangeFinder_Benewake : public AP_RangeFinder_Backend

// constructor
AP_RangeFinder_Benewake(RangeFinder::RangeFinder_State &_state,
AP_RangeFinder_Params &_params,
AP_SerialManager &serial_manager,
uint8_t serial_instance,
benewake_model_type model);
Expand Down
3 changes: 2 additions & 1 deletion libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.cpp
Expand Up @@ -25,9 +25,10 @@ extern const AP_HAL::HAL& hal;
already know that we should setup the rangefinder
*/
AP_RangeFinder_LeddarOne::AP_RangeFinder_LeddarOne(RangeFinder::RangeFinder_State &_state,
AP_RangeFinder_Params &_params,
AP_SerialManager &serial_manager,
uint8_t serial_instance) :
AP_RangeFinder_Backend(_state)
AP_RangeFinder_Backend(_state, _params)
{
uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance);
if (uart != nullptr) {
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.h
Expand Up @@ -43,6 +43,7 @@ class AP_RangeFinder_LeddarOne : public AP_RangeFinder_Backend
public:
// constructor
AP_RangeFinder_LeddarOne(RangeFinder::RangeFinder_State &_state,
AP_RangeFinder_Params &_params,
AP_SerialManager &serial_manager,
uint8_t serial_instance);

Expand Down
10 changes: 5 additions & 5 deletions libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.cpp
Expand Up @@ -26,23 +26,23 @@ extern const AP_HAL::HAL& hal;
constructor is not called until detect() returns true, so we
already know that we should setup the rangefinder
*/
AP_RangeFinder_LightWareI2C::AP_RangeFinder_LightWareI2C(RangeFinder::RangeFinder_State &_state, AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
: AP_RangeFinder_Backend(_state)
AP_RangeFinder_LightWareI2C::AP_RangeFinder_LightWareI2C(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params, AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
: AP_RangeFinder_Backend(_state, _params)
, _dev(std::move(dev)) {}

/*
detect if a Lightware 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_LightWareI2C::detect(RangeFinder::RangeFinder_State &_state, AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
AP_RangeFinder_Backend *AP_RangeFinder_LightWareI2C::detect(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params, AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
{
if (!dev) {
return nullptr;
}

AP_RangeFinder_LightWareI2C *sensor
= new AP_RangeFinder_LightWareI2C(_state, std::move(dev));
= new AP_RangeFinder_LightWareI2C(_state, _params, std::move(dev));

if (!sensor) {
delete sensor;
Expand Down Expand Up @@ -76,7 +76,7 @@ bool AP_RangeFinder_LightWareI2C::get_reading(uint16_t &reading_cm)
{
be16_t val;

if (state.address == 0) {
if (params.address == 0) {
return false;
}

Expand Down
3 changes: 2 additions & 1 deletion libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.h
Expand Up @@ -10,6 +10,7 @@ class AP_RangeFinder_LightWareI2C : public AP_RangeFinder_Backend
public:
// static detection function
static AP_RangeFinder_Backend *detect(RangeFinder::RangeFinder_State &_state,
AP_RangeFinder_Params &_params,
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);

// update state
Expand All @@ -23,7 +24,7 @@ class AP_RangeFinder_LightWareI2C : public AP_RangeFinder_Backend

private:
// constructor
AP_RangeFinder_LightWareI2C(RangeFinder::RangeFinder_State &_state, AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
AP_RangeFinder_LightWareI2C(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params, AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);

void init();
void timer();
Expand Down
3 changes: 2 additions & 1 deletion libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.cpp
Expand Up @@ -26,9 +26,10 @@ extern const AP_HAL::HAL& hal;
already know that we should setup the rangefinder
*/
AP_RangeFinder_LightWareSerial::AP_RangeFinder_LightWareSerial(RangeFinder::RangeFinder_State &_state,
AP_RangeFinder_Params &_params,
AP_SerialManager &serial_manager,
uint8_t serial_instance) :
AP_RangeFinder_Backend(_state)
AP_RangeFinder_Backend(_state, _params)
{
uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance);
if (uart != nullptr) {
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.h
Expand Up @@ -9,6 +9,7 @@ class AP_RangeFinder_LightWareSerial : public AP_RangeFinder_Backend
public:
// constructor
AP_RangeFinder_LightWareSerial(RangeFinder::RangeFinder_State &_state,
AP_RangeFinder_Params &_params,
AP_SerialManager &serial_manager,
uint8_t serial_instance);

Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.cpp
Expand Up @@ -25,8 +25,8 @@ extern const AP_HAL::HAL& hal;
constructor is not called until detect() returns true, so we
already know that we should setup the rangefinder
*/
AP_RangeFinder_MAVLink::AP_RangeFinder_MAVLink(RangeFinder::RangeFinder_State &_state) :
AP_RangeFinder_Backend(_state)
AP_RangeFinder_MAVLink::AP_RangeFinder_MAVLink(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) :
AP_RangeFinder_Backend(_state, _params)
{
state.last_reading_ms = AP_HAL::millis();
distance_cm = 0;
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.h
Expand Up @@ -11,7 +11,7 @@ class AP_RangeFinder_MAVLink : public AP_RangeFinder_Backend

public:
// constructor
AP_RangeFinder_MAVLink(RangeFinder::RangeFinder_State &_state);
AP_RangeFinder_MAVLink(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params);

// static detection function
static bool detect();
Expand Down
6 changes: 4 additions & 2 deletions libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.cpp
Expand Up @@ -37,8 +37,9 @@ extern const AP_HAL::HAL& hal;
already know that we should setup the rangefinder
*/
AP_RangeFinder_MaxsonarI2CXL::AP_RangeFinder_MaxsonarI2CXL(RangeFinder::RangeFinder_State &_state,
AP_RangeFinder_Params &_params,
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
: AP_RangeFinder_Backend(_state)
: AP_RangeFinder_Backend(_state, _params)
, _dev(std::move(dev))
{
}
Expand All @@ -49,14 +50,15 @@ AP_RangeFinder_MaxsonarI2CXL::AP_RangeFinder_MaxsonarI2CXL(RangeFinder::RangeFin
there.
*/
AP_RangeFinder_Backend *AP_RangeFinder_MaxsonarI2CXL::detect(RangeFinder::RangeFinder_State &_state,
AP_RangeFinder_Params &_params,
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
{
if (!dev) {
return nullptr;
}

AP_RangeFinder_MaxsonarI2CXL *sensor
= new AP_RangeFinder_MaxsonarI2CXL(_state, std::move(dev));
= new AP_RangeFinder_MaxsonarI2CXL(_state, _params, std::move(dev));
if (!sensor) {
return nullptr;
}
Expand Down
2 changes: 2 additions & 0 deletions libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.h
Expand Up @@ -12,6 +12,7 @@ class AP_RangeFinder_MaxsonarI2CXL : public AP_RangeFinder_Backend
public:
// static detection function
static AP_RangeFinder_Backend *detect(RangeFinder::RangeFinder_State &_state,
AP_RangeFinder_Params &_params,
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);

// update state
Expand All @@ -26,6 +27,7 @@ class AP_RangeFinder_MaxsonarI2CXL : public AP_RangeFinder_Backend
private:
// constructor
AP_RangeFinder_MaxsonarI2CXL(RangeFinder::RangeFinder_State &_state,
AP_RangeFinder_Params &_params,
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);

bool _init(void);
Expand Down
3 changes: 2 additions & 1 deletion libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.cpp
Expand Up @@ -30,9 +30,10 @@ extern const AP_HAL::HAL& hal;
already know that we should setup the rangefinder
*/
AP_RangeFinder_MaxsonarSerialLV::AP_RangeFinder_MaxsonarSerialLV(RangeFinder::RangeFinder_State &_state,
AP_RangeFinder_Params &_params,
AP_SerialManager &serial_manager,
uint8_t serial_instance) :
AP_RangeFinder_Backend(_state)
AP_RangeFinder_Backend(_state, _params)
{
uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance);
if (uart != nullptr) {
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.h
Expand Up @@ -9,6 +9,7 @@ class AP_RangeFinder_MaxsonarSerialLV : public AP_RangeFinder_Backend
public:
// constructor
AP_RangeFinder_MaxsonarSerialLV(RangeFinder::RangeFinder_State &_state,
AP_RangeFinder_Params &_params,
AP_SerialManager &serial_manager,
uint8_t serial_instance);

Expand Down
3 changes: 2 additions & 1 deletion libraries/AP_RangeFinder/AP_RangeFinder_NMEA.cpp
Expand Up @@ -25,9 +25,10 @@ extern const AP_HAL::HAL& hal;
// Note this is called after detect() returns true, so we
// already know that we should setup the rangefinder
AP_RangeFinder_NMEA::AP_RangeFinder_NMEA(RangeFinder::RangeFinder_State &_state,
AP_RangeFinder_Params &_params,
AP_SerialManager &serial_manager,
uint8_t serial_instance) :
AP_RangeFinder_Backend(_state),
AP_RangeFinder_Backend(_state, _params),
_distance_m(-1.0f)
{
uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance);
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_RangeFinder/AP_RangeFinder_NMEA.h
Expand Up @@ -24,6 +24,7 @@ class AP_RangeFinder_NMEA : public AP_RangeFinder_Backend
public:
// constructor
AP_RangeFinder_NMEA(RangeFinder::RangeFinder_State &_state,
AP_RangeFinder_Params &_params,
AP_SerialManager &serial_manager,
uint8_t serial_instance);

Expand Down