mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
AP_RangeFinder: allow re-init if no sensors found
needed for AP_Periph with slow startup sensors or sensors that power on separately to the CAN node
This commit is contained in:
parent
05c996bfcc
commit
e300db5be0
@ -185,11 +185,10 @@ RangeFinder::RangeFinder()
|
||||
*/
|
||||
void RangeFinder::init(enum Rotation orientation_default)
|
||||
{
|
||||
if (init_done) {
|
||||
// init called a 2nd time?
|
||||
if (num_instances != 0) {
|
||||
// don't re-init if we've found some sensors already
|
||||
return;
|
||||
}
|
||||
init_done = true;
|
||||
|
||||
// set orientation defaults
|
||||
for (uint8_t i=0; i<RANGEFINDER_MAX_INSTANCES; i++) {
|
||||
@ -298,9 +297,11 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
|
||||
#if AP_RANGEFINDER_LWI2C_ENABLED
|
||||
if (params[instance].address) {
|
||||
// the LW20 needs a long time to boot up, so we delay 1.5s here
|
||||
#ifndef HAL_BUILD_AP_PERIPH
|
||||
if (!hal.util->was_watchdog_armed()) {
|
||||
hal.scheduler->delay(1500);
|
||||
}
|
||||
#endif
|
||||
#ifdef HAL_RANGEFINDER_LIGHTWARE_I2C_BUS
|
||||
_add_backend(AP_RangeFinder_LightWareI2C::detect(state[instance], params[instance],
|
||||
hal.i2c_mgr->get_device(HAL_RANGEFINDER_LIGHTWARE_I2C_BUS, params[instance].address)),
|
||||
|
@ -219,7 +219,6 @@ private:
|
||||
RangeFinder_State state[RANGEFINDER_MAX_INSTANCES];
|
||||
AP_RangeFinder_Backend *drivers[RANGEFINDER_MAX_INSTANCES];
|
||||
uint8_t num_instances;
|
||||
bool init_done;
|
||||
HAL_Semaphore detect_sem;
|
||||
float estimated_terrain_height;
|
||||
Vector3f pos_offset_zero; // allows returning position offsets of zero for invalid requests
|
||||
|
Loading…
Reference in New Issue
Block a user