diff --git a/libraries/AP_RangeFinder/AP_RangeFinder.cpp b/libraries/AP_RangeFinder/AP_RangeFinder.cpp index 16e8f089c1fa1..3be3b18b475b0 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder.cpp @@ -241,6 +241,19 @@ void RangeFinder::update(void) continue; } drivers[i]->update(); + + WITH_SEMAPHORE(drivers[i]->get_semaphore()); + /* + ensure that all drivers timeout to NoData. If they are + currently in NotConnected state then leave it in that + state as they have never had any data + */ + const uint32_t last_update_ms = drivers[i]->last_reading_ms(); + const uint32_t now_ms = AP_HAL::millis(); + if (state[i].status != Status::NotConnected && + now_ms - last_update_ms > drivers[i]->read_timeout_ms()) { + state[i].status = Status::NoData; + } } } #if HAL_LOGGING_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_BLPing.h b/libraries/AP_RangeFinder/AP_RangeFinder_BLPing.h index 04fccaae4e35e..dfe507d594d76 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_BLPing.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_BLPing.h @@ -180,7 +180,7 @@ class AP_RangeFinder_BLPing : public AP_RangeFinder_Backend_Serial * * @return uint16_t */ - uint16_t read_timeout_ms() const override { return 1000; } + uint32_t read_timeout_ms() const override { return 1000; } /** * @brief system time that sensor was last initialised diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Backend.h b/libraries/AP_RangeFinder/AP_RangeFinder_Backend.h index ca2decd044e30..16294d94bec51 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Backend.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Backend.h @@ -79,6 +79,12 @@ class AP_RangeFinder_Backend // parameter value which may be changed at runtime. RangeFinder::Type allocated_type() const { return _backend_type; } + // maximum time between readings before we change state to NoData: + virtual uint32_t read_timeout_ms() const { return 200; } + + // get reference to driver semaphore + HAL_Semaphore &get_semaphore(void) { return _sem; } + protected: // update status based on distance measurement diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Backend_CAN.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_Backend_CAN.cpp index 659a4af199106..494ff77dc7b7a 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Backend_CAN.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Backend_CAN.cpp @@ -58,8 +58,6 @@ void AP_RangeFinder_Backend_CAN::update(void) // update range_valid state based on distance measured state.last_reading_ms = AP_HAL::millis(); update_status(); - } else if (AP_HAL::millis() - state.last_reading_ms >= read_timeout_ms()) { - set_status(RangeFinder::Status::NoData); } } diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Backend_CAN.h b/libraries/AP_RangeFinder/AP_RangeFinder_Backend_CAN.h index 96d62aa94dedf..4d3b690f6a2e8 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Backend_CAN.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Backend_CAN.h @@ -32,9 +32,6 @@ class AP_RangeFinder_Backend_CAN : public AP_RangeFinder_Backend // it is essential that anyone relying on the base-class update to implement this virtual bool handle_frame(AP_HAL::CANFrame &frame) = 0; - // maximum time between readings before we change state to NoData: - virtual uint32_t read_timeout_ms() const { return 200; } - virtual MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const override { return MAV_DISTANCE_SENSOR_RADAR; } diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Backend_Serial.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_Backend_Serial.cpp index af27aaf5a7ad4..913d58e2b3a89 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Backend_Serial.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Backend_Serial.cpp @@ -57,7 +57,5 @@ void AP_RangeFinder_Backend_Serial::update(void) // update range_valid state based on distance measured state.last_reading_ms = AP_HAL::millis(); update_status(); - } else if (AP_HAL::millis() - state.last_reading_ms > read_timeout_ms()) { - set_status(RangeFinder::Status::NoData); } } diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Backend_Serial.h b/libraries/AP_RangeFinder/AP_RangeFinder_Backend_Serial.h index e4349d75b8a8f..1219028829bf9 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Backend_Serial.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Backend_Serial.h @@ -34,7 +34,4 @@ class AP_RangeFinder_Backend_Serial : public AP_RangeFinder_Backend // Like get_reading() this method is called in the base-class update() method. virtual int8_t get_signal_quality_pct() const WARN_IF_UNUSED { return RangeFinder::SIGNAL_QUALITY_UNKNOWN; } - - // maximum time between readings before we change state to NoData: - virtual uint16_t read_timeout_ms() const { return 200; } }; diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TFMiniPlus.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TFMiniPlus.cpp index fc4e227c74b05..bfa2d597322e8 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TFMiniPlus.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake_TFMiniPlus.cpp @@ -148,8 +148,6 @@ void AP_RangeFinder_Benewake_TFMiniPlus::update() accum.sum = 0; accum.count = 0; update_status(); - } else if (AP_HAL::millis() - state.last_reading_ms > 200) { - set_status(RangeFinder::Status::NoData); } } diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.cpp index 4db29571beda1..49ee91b4a8390 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.cpp @@ -84,10 +84,7 @@ AP_RangeFinder_DroneCAN* AP_RangeFinder_DroneCAN::get_dronecan_backend(AP_DroneC void AP_RangeFinder_DroneCAN::update() { WITH_SEMAPHORE(_sem); - if ((AP_HAL::millis() - _last_reading_ms) > 500) { - //if data is older than 500ms, report NoData - set_status(RangeFinder::Status::NoData); - } else if (_status == RangeFinder::Status::Good && new_data) { + if (_status == RangeFinder::Status::Good && new_data) { //copy over states state.distance_m = _distance_cm * 0.01f; state.last_reading_ms = _last_reading_ms; diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.h b/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.h index 6d763b2b97fba..a5f3beaac2f39 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_DroneCAN.h @@ -22,6 +22,9 @@ class AP_RangeFinder_DroneCAN : public AP_RangeFinder_Backend { static void handle_measurement(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const uavcan_equipment_range_sensor_Measurement &msg); + // maximum time between readings before we change state to NoData: + uint32_t read_timeout_ms() const override { return 500; } + protected: virtual MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const override { return _sensor_type; diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_HC_SR04.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_HC_SR04.cpp index 6e7cc156ec47a..17af4e3a74734 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_HC_SR04.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_HC_SR04.cpp @@ -97,13 +97,7 @@ void AP_RangeFinder_HC_SR04::update(void) const uint32_t value_us = pwm_source.get_pwm_us(); const uint32_t now = AP_HAL::millis(); - if (value_us == 0) { - // no reading; check for timeout: - if (now - last_reading_ms > 1000) { - // no reading for a second - something is broken - state.distance_m = 0.0f; - } - } else { + if (value_us != 0) { // gcs().send_text(MAV_SEVERITY_WARNING, "Pong!"); // a new reading - convert time to distance state.distance_m = (value_us * (1.0/58.0f)) * 0.01f; // 58 is from datasheet, mult for performance @@ -126,10 +120,10 @@ void AP_RangeFinder_HC_SR04::update(void) } last_reading_ms = now; - } - // update range_valid state based on distance measured - update_status(); + // update range_valid state based on distance measured + update_status(); + } // consider sending new ping if (now - last_ping_ms > 67) { // read ~@15Hz - recommended 60ms delay from datasheet diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_LeddarVu8.h b/libraries/AP_RangeFinder/AP_RangeFinder_LeddarVu8.h index 68db11394ebc3..ce0459019c73f 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_LeddarVu8.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_LeddarVu8.h @@ -36,7 +36,7 @@ class AP_RangeFinder_LeddarVu8 : public AP_RangeFinder_Backend_Serial bool get_reading(float &reading_m) override; // maximum time between readings before we change state to NoData: - uint16_t read_timeout_ms() const override { return 500; } + uint32_t read_timeout_ms() const override { return 500; } private: diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.cpp index 725b76f4f63ad..47f454f029af4 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.cpp @@ -465,21 +465,23 @@ void AP_RangeFinder_LightWareI2C::update(void) void AP_RangeFinder_LightWareI2C::legacy_timer(void) { - if (legacy_get_reading(state.distance_m)) { + float distance_m = 0; + if (legacy_get_reading(distance_m)) { // update range_valid state based on distance measured + WITH_SEMAPHORE(_sem); + state.distance_m = distance_m; update_status(); - } else { - set_status(RangeFinder::Status::NoData); } } void AP_RangeFinder_LightWareI2C::sf20_timer(void) { - if (sf20_get_reading(state.distance_m)) { + float distance_m = 0; + if (sf20_get_reading(distance_m)) { // update range_valid state based on distance measured + WITH_SEMAPHORE(_sem); + state.distance_m = distance_m; update_status(); - } else { - set_status(RangeFinder::Status::NoData); } } diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Lua.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_Lua.cpp index 75e22b2aaba5f..8a56f82292c81 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Lua.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Lua.cpp @@ -48,16 +48,11 @@ bool AP_RangeFinder_Lua::handle_script_msg(float dist_m) { WITH_SEMAPHORE(_sem); - // Time out on incoming data; if we don't get new data in 500ms, dump it - if (now - _state_pending.last_reading_ms > AP_RANGEFINDER_LUA_TIMEOUT_MS) { - set_status(_state_pending, RangeFinder::Status::NoData); - } else { - _state_pending.last_reading_ms = now; - _state_pending.distance_m = dist_m; - _state_pending.signal_quality_pct = RangeFinder::SIGNAL_QUALITY_UNKNOWN; - _state_pending.voltage_mv = 0; - update_status(_state_pending); - } + _state_pending.last_reading_ms = now; + _state_pending.distance_m = dist_m; + _state_pending.signal_quality_pct = RangeFinder::SIGNAL_QUALITY_UNKNOWN; + _state_pending.voltage_mv = 0; + update_status(_state_pending); return true; } diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Lua.h b/libraries/AP_RangeFinder/AP_RangeFinder_Lua.h index 0bd7f7a1acb6b..dc3208497f3a8 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Lua.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Lua.h @@ -27,6 +27,9 @@ class AP_RangeFinder_Lua : public AP_RangeFinder_Backend return MAV_DISTANCE_SENSOR_UNKNOWN; } + // maximum time between readings before we change state to NoData: + uint32_t read_timeout_ms() const override { return AP_RANGEFINDER_LUA_TIMEOUT_MS; } + private: RangeFinder::RangeFinder_State _state_pending = {}; diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.cpp index b4fc5fb1ff597..cbefdb3dae98b 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.cpp @@ -42,6 +42,10 @@ void AP_RangeFinder_MAVLink::handle_msg(const mavlink_message_t &msg) // Map 1 to 0 as that is what ardupilot uses as the worst signal quality signal_quality = RangeFinder::SIGNAL_QUALITY_MIN; } + WITH_SEMAPHORE(_sem); + state.distance_m = distance_cm * 0.01f; + state.signal_quality_pct = signal_quality; + update_status(); } } @@ -69,22 +73,4 @@ int16_t AP_RangeFinder_MAVLink::min_distance_cm() const return _min_distance_cm; } -/* - update the state of the sensor -*/ -void AP_RangeFinder_MAVLink::update(void) -{ - //Time out on incoming data; if we don't get new - //data in 500ms, dump it - if (AP_HAL::millis() - state.last_reading_ms > AP_RANGEFINDER_MAVLINK_TIMEOUT_MS) { - set_status(RangeFinder::Status::NoData); - state.distance_m = 0.0f; - state.signal_quality_pct = RangeFinder::SIGNAL_QUALITY_UNKNOWN; - } else { - state.distance_m = distance_cm * 0.01f; - state.signal_quality_pct = signal_quality; - update_status(); - } -} - #endif diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.h b/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.h index 47cd080c13f9a..8e3b268b83320 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.h @@ -22,8 +22,8 @@ class AP_RangeFinder_MAVLink : public AP_RangeFinder_Backend // there is an attached MAVLink rangefinder static bool detect() { return true; } - // update state - void update(void) override; + // empty update + void update(void) override {} // Get update from mavlink void handle_msg(const mavlink_message_t &msg) override; @@ -31,6 +31,8 @@ class AP_RangeFinder_MAVLink : public AP_RangeFinder_Backend int16_t max_distance_cm() const override; int16_t min_distance_cm() const override; + uint32_t read_timeout_ms() const override { return AP_RANGEFINDER_MAVLINK_TIMEOUT_MS; } + protected: MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const override { diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MSP.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_MSP.cpp index e5ee32bdc5a39..26f188c70e289 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_MSP.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MSP.cpp @@ -29,7 +29,6 @@ AP_RangeFinder_MSP::AP_RangeFinder_MSP(RangeFinder::RangeFinder_State &_state, A AP_RangeFinder_Backend(_state, _params) { state.last_reading_ms = AP_HAL::millis(); - distance_cm = 0; } /* @@ -48,24 +47,10 @@ bool AP_RangeFinder_MSP::detect() */ void AP_RangeFinder_MSP::handle_msp(const MSP::msp_rangefinder_data_message_t &pkt) { + WITH_SEMAPHORE(_sem); + state.distance_m = pkt.distance_mm * 0.001f; state.last_reading_ms = AP_HAL::millis(); - distance_cm = pkt.distance_mm / 10; -} - -/* - update the state of the sensor -*/ -void AP_RangeFinder_MSP::update(void) -{ - //Time out on incoming data; if we don't get new - //data in 500ms, dump it - if (AP_HAL::millis() - state.last_reading_ms > AP_RANGEFINDER_MSP_TIMEOUT_MS) { - set_status(RangeFinder::Status::NoData); - state.distance_m = 0.0f; - } else { - state.distance_m = distance_cm * 0.01f; - update_status(); - } + update_status(); } #endif //HAL_MSP_RANGEFINDER_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MSP.h b/libraries/AP_RangeFinder/AP_RangeFinder_MSP.h index 59643fe69684e..688b2477d3967 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_MSP.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MSP.h @@ -20,12 +20,14 @@ class AP_RangeFinder_MSP : public AP_RangeFinder_Backend // static detection function static bool detect(); - // update state - void update(void) override; + // empty update + void update(void) override {} // Get update from msp void handle_msp(const MSP::msp_rangefinder_data_message_t &pkt) override; + uint32_t read_timeout_ms() const override { return AP_RANGEFINDER_MSP_TIMEOUT_MS; } + protected: MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const override { @@ -33,8 +35,6 @@ class AP_RangeFinder_MSP : public AP_RangeFinder_Backend } private: - uint16_t distance_cm; - // start a reading static bool start_reading(void); static bool get_reading(uint16_t &reading_cm); diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.cpp index 1cb7cdc5af66b..e387ccc026556 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.cpp @@ -148,9 +148,6 @@ void AP_RangeFinder_MaxsonarI2CXL::update(void) state.distance_m = distance * 0.01f; new_distance = false; update_status(); - } else if (AP_HAL::millis() - state.last_reading_ms > 300) { - // if no updates for 0.3 seconds set no-data - set_status(RangeFinder::Status::NoData); } } diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.h b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.h index 7648133963f8d..0c07284a90c05 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.h @@ -23,6 +23,8 @@ class AP_RangeFinder_MaxsonarI2CXL : public AP_RangeFinder_Backend // update state void update(void) override; + uint32_t read_timeout_ms() const override { return 300; } + protected: MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const override { diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.h b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.h index b0693c11e3247..46a8e437b75b6 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.h @@ -31,7 +31,7 @@ class AP_RangeFinder_MaxsonarSerialLV : public AP_RangeFinder_Backend_Serial // get a reading bool get_reading(float &reading_m) override; - uint16_t read_timeout_ms() const override { return 500; } + uint32_t read_timeout_ms() const override { return 500; } char linebuf[10]; uint8_t linebuf_len = 0; diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_NMEA.h b/libraries/AP_RangeFinder/AP_RangeFinder_NMEA.h index d8c7ff3d14520..f847f5ffc83e2 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_NMEA.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_NMEA.h @@ -58,7 +58,7 @@ class AP_RangeFinder_NMEA : public AP_RangeFinder_Backend_Serial // get temperature reading in C. returns true on success and populates temp argument bool get_temp(float &temp) const override; - uint16_t read_timeout_ms() const override { return 3000; } + uint32_t read_timeout_ms() const override { return 3000; } // add a single character to the buffer and attempt to decode // returns true if a distance was successfully decoded diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_NRA24_CAN.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_NRA24_CAN.cpp index 30f170adddc9d..9a6092b28f52e 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_NRA24_CAN.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_NRA24_CAN.cpp @@ -14,15 +14,6 @@ void AP_RangeFinder_NRA24_CAN::update(void) // update range_valid state based on distance measured state.last_reading_ms = AP_HAL::millis(); update_status(); - } else if (AP_HAL::millis() - state.last_reading_ms > read_timeout_ms()) { - if (AP_HAL::millis() - last_heartbeat_ms > read_timeout_ms()) { - // no heartbeat, must be disconnected - set_status(RangeFinder::Status::NotConnected); - } else { - // Have heartbeat, just no data. Probably because this sensor doesn't output data when there is no relative motion infront of the radar. - // This case has special pre-arm check handling - set_status(RangeFinder::Status::NoData); - } } } diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_PWM.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_PWM.cpp index 97352b2d4a83b..03eda44cd89d5 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_PWM.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_PWM.cpp @@ -114,9 +114,6 @@ void AP_RangeFinder_PWM::update(void) if (!get_reading(state.distance_m)) { // failure; consider changing our state - if (AP_HAL::millis() - state.last_reading_ms > 200) { - set_status(RangeFinder::Status::NoData); - } return; } // add offset diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.cpp index 5c9cbb38a9a2a..ac5b8a2e6973d 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.cpp @@ -96,8 +96,6 @@ void AP_RangeFinder_PulsedLightLRF::timer(void) state.distance_m = filter.apply(_distance_cm*0.01); state.last_reading_ms = AP_HAL::millis(); update_status(); - } else if (AP_HAL::millis() - state.last_reading_ms > 200) { - set_status(RangeFinder::Status::NoData); } if (!v2_hardware) { // for v2 hw we use continuous mode diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_SITL.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_SITL.cpp index a4e5f30493b20..dd7a214ef51dd 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_SITL.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_SITL.cpp @@ -36,7 +36,6 @@ void AP_RangeFinder_SITL::update(void) // nan distance means nothing is connected if (isnan(dist) || isinf(dist)) { - state.status = RangeFinder::Status::NoData; return; } diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_TOFSenseF_I2C.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_TOFSenseF_I2C.cpp index 55f0e497d62f0..40017e754ac05 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_TOFSenseF_I2C.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_TOFSenseF_I2C.cpp @@ -150,9 +150,6 @@ void AP_RangeFinder_TOFSenseF_I2C::update(void) state.distance_m = distance_mm * 0.001f; new_distance = false; update_status(); - } else if (AP_HAL::millis() - state.last_reading_ms > 300) { - // if no updates for 0.3 seconds set no-data - set_status(RangeFinder::Status::NoData); } } diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_TOFSenseF_I2C.h b/libraries/AP_RangeFinder/AP_RangeFinder_TOFSenseF_I2C.h index 7f72f13108712..6623fe93de6c7 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_TOFSenseF_I2C.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_TOFSenseF_I2C.h @@ -22,6 +22,8 @@ class AP_RangeFinder_TOFSenseF_I2C : public AP_RangeFinder_Backend // update state void update(void) override; + uint32_t read_timeout_ms() const override { return 300; } + protected: MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const override { diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_TeraRangerI2C.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_TeraRangerI2C.cpp index c1772bfbad1f9..438714334e10e 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_TeraRangerI2C.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_TeraRangerI2C.cpp @@ -187,8 +187,6 @@ void AP_RangeFinder_TeraRangerI2C::update(void) accum.sum = 0; accum.count = 0; update_status(); - } else if (AP_HAL::millis() - state.last_reading_ms > 200) { - set_status(RangeFinder::Status::NoData); } } diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_VL53L0X.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_VL53L0X.cpp index 51c10dec8cd00..bedc5087ff0a2 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_VL53L0X.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_VL53L0X.cpp @@ -763,21 +763,21 @@ uint16_t AP_RangeFinder_VL53L0X::read_register16(uint8_t reg) */ void AP_RangeFinder_VL53L0X::update(void) { + WITH_SEMAPHORE(_sem); if (counter > 0) { state.distance_m = (sum_mm * 0.001f) / counter; state.last_reading_ms = AP_HAL::millis(); sum_mm = 0; counter = 0; update_status(); - } else { - set_status(RangeFinder::Status::NoData); } } void AP_RangeFinder_VL53L0X::timer(void) { - uint16_t range_mm; + uint16_t range_mm; if (get_reading(range_mm) && range_mm < 8000) { + WITH_SEMAPHORE(_sem); sum_mm += range_mm; counter++; } diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_VL53L1X.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_VL53L1X.cpp index e0eba359eee8f..1ed8425116095 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_VL53L1X.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_VL53L1X.cpp @@ -575,9 +575,6 @@ void AP_RangeFinder_VL53L1X::update(void) update_status(); sum_mm = 0; counter = 0; - } else if (AP_HAL::millis() - state.last_reading_ms > 200) { - // if no updates for 0.2s set no-data - set_status(RangeFinder::Status::NoData); } } diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Wasp.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_Wasp.cpp index 5885b2af14625..0fddcd994b8de 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Wasp.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Wasp.cpp @@ -131,9 +131,7 @@ bool AP_RangeFinder_Wasp::get_reading(float &reading_m) { #define COMMAND_BUFFER_LEN 15 void AP_RangeFinder_Wasp::update(void) { - if (!get_reading(state.distance_m)) { - set_status(RangeFinder::Status::NoData); - } + get_reading(state.distance_m); if (AP_HAL::millis() - state.last_reading_ms > 500) { // attempt to reconfigure on the assumption this was a bad baud setting