diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_BBB_PRU.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_BBB_PRU.cpp index c1ffbb74a7..09d3b3d0de 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_BBB_PRU.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_BBB_PRU.cpp @@ -116,5 +116,6 @@ void AP_RangeFinder_BBB_PRU::update(void) { state.status = (RangeFinder::RangeFinder_Status)rangerpru->status; state.distance_cm = rangerpru->distance; + state.last_reading_ms = AP_HAL::millis(); } #endif // CONFIG_HAL_BOARD_SUBTYPE diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Bebop.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_Bebop.cpp index 2985241422..b2a55953c1 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Bebop.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Bebop.cpp @@ -267,6 +267,7 @@ void AP_RangeFinder_Bebop::update(void) } state.distance_cm = (uint16_t) (_altitude * 100); + state.last_reading_ms = AP_HAL::millis(); update_status(); } diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake.cpp index beab025f6d..84a56d6476 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake.cpp @@ -152,14 +152,14 @@ void AP_RangeFinder_Benewake::update(void) bool signal_ok; if (get_reading(state.distance_cm, signal_ok)) { // update range_valid state based on distance measured - last_reading_ms = AP_HAL::millis(); + state.last_reading_ms = AP_HAL::millis(); if (signal_ok) { update_status(); } else { // if signal is weak set status to out-of-range set_status(RangeFinder::RangeFinder_OutOfRangeHigh); } - } else if (AP_HAL::millis() - last_reading_ms > 200) { + } else if (AP_HAL::millis() - state.last_reading_ms > 200) { set_status(RangeFinder::RangeFinder_NoData); } } diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake.h b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake.h index b61a66ebb7..6641866934 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake.h @@ -39,7 +39,6 @@ private: AP_HAL::UARTDriver *uart = nullptr; benewake_model_type model_type; - uint32_t last_reading_ms; char linebuf[10]; uint8_t linebuf_len; }; diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.cpp index 4d9db6080f..8ec49ca1af 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.cpp @@ -128,9 +128,9 @@ void AP_RangeFinder_LeddarOne::update(void) { if (get_reading(state.distance_cm)) { // update range_valid state based on distance measured - last_reading_ms = AP_HAL::millis(); + state.last_reading_ms = AP_HAL::millis(); update_status(); - } else if (AP_HAL::millis() - last_reading_ms > 200) { + } else if (AP_HAL::millis() - state.last_reading_ms > 200) { set_status(RangeFinder::RangeFinder_NoData); } } diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.h b/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.h index 3ce2de4c49..19c1bb4a55 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.h @@ -69,7 +69,6 @@ private: LeddarOne_Status parse_response(uint8_t &number_detections); AP_HAL::UARTDriver *uart = nullptr; - uint32_t last_reading_ms; uint32_t last_sending_request_ms; uint32_t last_available_ms; diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.cpp index 5c097eb74b..a37293eaa3 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.cpp @@ -97,6 +97,7 @@ void AP_RangeFinder_LightWareI2C::update(void) void AP_RangeFinder_LightWareI2C::timer(void) { if (get_reading(state.distance_cm)) { + state.last_reading_ms = AP_HAL::millis(); // update range_valid state based on distance measured update_status(); } else { diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.cpp index d8e8c295df..313ae05c68 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.cpp @@ -90,9 +90,9 @@ void AP_RangeFinder_LightWareSerial::update(void) { if (get_reading(state.distance_cm)) { // update range_valid state based on distance measured - last_reading_ms = AP_HAL::millis(); + state.last_reading_ms = AP_HAL::millis(); update_status(); - } else if (AP_HAL::millis() - last_reading_ms > 200) { + } else if (AP_HAL::millis() - state.last_reading_ms > 200) { set_status(RangeFinder::RangeFinder_NoData); } } diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.h b/libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.h index 0b2ddd2c79..d3590cd363 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.h @@ -29,7 +29,6 @@ private: bool get_reading(uint16_t &reading_cm); AP_HAL::UARTDriver *uart = nullptr; - uint32_t last_reading_ms = 0; char linebuf[10]; uint8_t linebuf_len = 0; }; diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.cpp index f6a902943a..7eef8875de 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.cpp @@ -28,7 +28,7 @@ extern const AP_HAL::HAL& hal; AP_RangeFinder_MAVLink::AP_RangeFinder_MAVLink(RangeFinder::RangeFinder_State &_state) : AP_RangeFinder_Backend(_state) { - last_update_ms = AP_HAL::millis(); + state.last_reading_ms = AP_HAL::millis(); distance_cm = 0; } @@ -53,7 +53,7 @@ void AP_RangeFinder_MAVLink::handle_msg(mavlink_message_t *msg) // only accept distances for downward facing sensors if (packet.orientation == MAV_SENSOR_ROTATION_PITCH_270) { - last_update_ms = AP_HAL::millis(); + state.last_reading_ms = AP_HAL::millis(); distance_cm = packet.current_distance; } sensor_type = (MAV_DISTANCE_SENSOR)packet.type; @@ -66,7 +66,7 @@ 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() - last_update_ms > AP_RANGEFINDER_MAVLINK_TIMEOUT_MS) { + if (AP_HAL::millis() - state.last_reading_ms > AP_RANGEFINDER_MAVLINK_TIMEOUT_MS) { set_status(RangeFinder::RangeFinder_NoData); state.distance_cm = 0; } else { diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.h b/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.h index 3453e813a3..829a1298c2 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.h @@ -30,7 +30,6 @@ protected: private: uint16_t distance_cm; - uint32_t last_update_ms; // start a reading static bool start_reading(void); diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.cpp index 8261849520..fcb234be67 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.cpp @@ -133,7 +133,7 @@ void AP_RangeFinder_MaxsonarI2CXL::_timer(void) if (_sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) { distance = d; new_distance = true; - last_update_ms = AP_HAL::millis(); + state.last_reading_ms = AP_HAL::millis(); _sem->give(); } } @@ -149,7 +149,7 @@ void AP_RangeFinder_MaxsonarI2CXL::update(void) state.distance_cm = distance; new_distance = false; update_status(); - } else if (AP_HAL::millis() - last_update_ms > 300) { + } else if (AP_HAL::millis() - state.last_reading_ms > 300) { // if no updates for 0.3 seconds set no-data set_status(RangeFinder::RangeFinder_NoData); } diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.h b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.h index c20cd02ae9..01b5ed4fa1 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.h @@ -33,7 +33,6 @@ private: uint16_t distance; bool new_distance; - uint32_t last_update_ms; // start a reading bool start_reading(void); diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.cpp index 21d3bfcaef..8d758a4c1e 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.cpp @@ -94,9 +94,9 @@ void AP_RangeFinder_MaxsonarSerialLV::update(void) { if (get_reading(state.distance_cm)) { // update range_valid state based on distance measured - last_reading_ms = AP_HAL::millis(); + state.last_reading_ms = AP_HAL::millis(); update_status(); - } else if (AP_HAL::millis() - last_reading_ms > 500) { + } else if (AP_HAL::millis() - state.last_reading_ms > 500) { set_status(RangeFinder::RangeFinder_NoData); } } diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.h b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.h index ed1ce832ba..c374986044 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.h @@ -29,7 +29,6 @@ private: bool get_reading(uint16_t &reading_cm); AP_HAL::UARTDriver *uart = nullptr; - uint32_t last_reading_ms = 0; char linebuf[10]; uint8_t linebuf_len = 0; }; diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_NMEA.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_NMEA.cpp index 4cce84aacf..143a400bc2 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_NMEA.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_NMEA.cpp @@ -48,9 +48,9 @@ void AP_RangeFinder_NMEA::update(void) uint32_t now = AP_HAL::millis(); if (get_reading(state.distance_cm)) { // update range_valid state based on distance measured - _last_reading_ms = now; + state.last_reading_ms = now; update_status(); - } else if ((now - _last_reading_ms) > 3000) { + } else if ((now - state.last_reading_ms) > 3000) { set_status(RangeFinder::RangeFinder_NoData); } } diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_NMEA.h b/libraries/AP_RangeFinder/AP_RangeFinder_NMEA.h index 4fbea9cbc5..7d19af3b22 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_NMEA.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_NMEA.h @@ -64,7 +64,6 @@ private: static int16_t char_to_hex(char a); AP_HAL::UARTDriver *uart = nullptr; // pointer to serial uart - uint32_t _last_reading_ms; // system time of last successful reading // message decoding related members char _term[15]; // buffer for the current term within the current sentence diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_PX4_PWM.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_PX4_PWM.cpp index 5c61fbe6d8..89c2110f74 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_PX4_PWM.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_PX4_PWM.cpp @@ -114,7 +114,7 @@ void AP_RangeFinder_PX4_PWM::update(void) // pulse widths in the log state.voltage_mv = pwm.pulse_width; - _last_pulse_time_ms = now; + state.last_reading_ms = now; // setup for scaling in meters per millisecond float _distance_cm = pwm.pulse_width * 0.1f * scaling + state.offset; @@ -162,9 +162,9 @@ void AP_RangeFinder_PX4_PWM::update(void) probably dead. Try resetting it. Tests show the sensor takes about 0.2s to boot, so 500ms offers some safety margin */ - if (now - _last_pulse_time_ms > 500U && _disable_time_ms == 0) { + if (now - state.last_reading_ms > 500U && _disable_time_ms == 0) { ioctl(_fd, SENSORIOCRESET, 0); - _last_pulse_time_ms = now; + state.last_reading_ms = now; // if a stop pin is configured then disable the sensor for the // settle time @@ -185,7 +185,7 @@ void AP_RangeFinder_PX4_PWM::update(void) (now - _disable_time_ms > settle_time_ms)) { hal.gpio->write(stop_pin, true); _disable_time_ms = 0; - _last_pulse_time_ms = now; + state.last_reading_ms = now; } if (count != 0) { diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_PX4_PWM.h b/libraries/AP_RangeFinder/AP_RangeFinder_PX4_PWM.h index 1511bd29e5..9950771ee1 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_PX4_PWM.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_PX4_PWM.h @@ -41,7 +41,6 @@ protected: private: int _fd; uint64_t _last_timestamp; - uint64_t _last_pulse_time_ms; uint32_t _disable_time_ms; uint32_t _good_sample_count; float _last_sample_distance_cm; diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.cpp index 963d3f9197..1fce36cd91 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.cpp @@ -100,6 +100,7 @@ void AP_RangeFinder_PulsedLightLRF::timer(void) // remove momentary spikes if (abs(_distance_cm - last_distance_cm) < 100) { state.distance_cm = _distance_cm; + state.last_reading_ms = AP_HAL::millis(); update_status(); } last_distance_cm = _distance_cm; diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_TeraRangerI2C.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_TeraRangerI2C.cpp index 3d654a4a87..ea617114c4 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_TeraRangerI2C.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_TeraRangerI2C.cpp @@ -160,7 +160,7 @@ void AP_RangeFinder_TeraRangerI2C::timer(void) uint16_t _distance_cm = 0; if (collect_raw(_raw_distance) && _sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) { - if(process_raw_measure(_raw_distance, _distance_cm)){ + if (process_raw_measure(_raw_distance, _distance_cm)){ accum.sum += _distance_cm; accum.count++; } @@ -178,6 +178,7 @@ void AP_RangeFinder_TeraRangerI2C::update(void) if (_sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) { if (accum.count > 0) { state.distance_cm = accum.sum / accum.count; + state.last_reading_ms = AP_HAL::millis(); accum.sum = 0; accum.count = 0; update_status(); diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_VL53L0X.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_VL53L0X.cpp index 8a2fee97a0..2476578362 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_VL53L0X.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_VL53L0X.cpp @@ -768,6 +768,7 @@ void AP_RangeFinder_VL53L0X::update(void) { if (counter > 0) { state.distance_cm = sum_mm / (10*counter); + state.last_reading_ms = AP_HAL::millis(); sum_mm = 0; counter = 0; update_status(); diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Wasp.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_Wasp.cpp index 0c6e6f0477..258dfbb6ae 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Wasp.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Wasp.cpp @@ -103,7 +103,7 @@ bool AP_RangeFinder_Wasp::get_reading(uint16_t &reading_cm) { if (c == '\n') { linebuf[linebuf_len] = 0; linebuf_len = 0; - last_reading_ms = AP_HAL::millis(); + state.last_reading_ms = AP_HAL::millis(); if (isalpha(linebuf[0])) { parse_response(); } else { @@ -144,7 +144,7 @@ void AP_RangeFinder_Wasp::update(void) { set_status(RangeFinder::RangeFinder_NoData); } - if (AP_HAL::millis() - last_reading_ms > 500) { + if (AP_HAL::millis() - state.last_reading_ms > 500) { // attempt to reconfigure on the assumption this was a bad baud setting configuration_state = WASP_CFG_RATE; } diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Wasp.h b/libraries/AP_RangeFinder/AP_RangeFinder_Wasp.h index 4be2327b1c..368e9b5c08 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Wasp.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Wasp.h @@ -49,7 +49,6 @@ private: void parse_response(void); AP_HAL::UARTDriver *uart; - uint32_t last_reading_ms; char linebuf[10]; uint8_t linebuf_len; AP_Int16 mavg; diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_analog.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_analog.cpp index 50906c1f04..1a781d615f 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_analog.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_analog.cpp @@ -115,7 +115,8 @@ void AP_RangeFinder_analog::update(void) if (dist_m < 0) { dist_m = 0; } - state.distance_cm = dist_m * 100.0f; + state.distance_cm = dist_m * 100.0f; + state.last_reading_ms = AP_HAL::millis(); // update range_valid state based on distance measured update_status(); diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_uLanding.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_uLanding.cpp index dc2d699c53..74141ac275 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_uLanding.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_uLanding.cpp @@ -211,10 +211,10 @@ bool AP_RangeFinder_uLanding::get_reading(uint16_t &reading_cm) void AP_RangeFinder_uLanding::update(void) { if (get_reading(state.distance_cm)) { + state.last_reading_ms = AP_HAL::millis(); // update range_valid state based on distance measured - _last_reading_ms = AP_HAL::millis(); update_status(); - } else if (AP_HAL::millis() - _last_reading_ms > 200) { + } else if (AP_HAL::millis() - state.last_reading_ms > 200) { set_status(RangeFinder::RangeFinder_NoData); } } diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_uLanding.h b/libraries/AP_RangeFinder/AP_RangeFinder_uLanding.h index dddc65d210..af973deba2 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_uLanding.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_uLanding.h @@ -34,7 +34,6 @@ private: AP_HAL::UARTDriver *uart; uint8_t _linebuf[6]; uint8_t _linebuf_len; - uint32_t _last_reading_ms; bool _version_known; uint8_t _header; uint8_t _version; diff --git a/libraries/AP_RangeFinder/RangeFinder.cpp b/libraries/AP_RangeFinder/RangeFinder.cpp index d354467a01..376493c5d4 100644 --- a/libraries/AP_RangeFinder/RangeFinder.cpp +++ b/libraries/AP_RangeFinder/RangeFinder.cpp @@ -910,6 +910,15 @@ const Vector3f &RangeFinder::get_pos_offset_orient(enum Rotation orientation) co return backend->get_pos_offset(); } +uint32_t RangeFinder::last_reading_ms(enum Rotation orientation) const +{ + AP_RangeFinder_Backend *backend = find_instance(orientation); + if (backend == nullptr) { + return 0; + } + return backend->last_reading_ms(); +} + MAV_DISTANCE_SENSOR RangeFinder::get_mav_distance_sensor_type_orient(enum Rotation orientation) const { AP_RangeFinder_Backend *backend = find_instance(orientation); diff --git a/libraries/AP_RangeFinder/RangeFinder.h b/libraries/AP_RangeFinder/RangeFinder.h index 2054dcecd9..391c66b846 100644 --- a/libraries/AP_RangeFinder/RangeFinder.h +++ b/libraries/AP_RangeFinder/RangeFinder.h @@ -87,6 +87,7 @@ public: bool pre_arm_check; // true if sensor has passed pre-arm checks uint16_t pre_arm_distance_min; // min distance captured during pre-arm checks uint16_t pre_arm_distance_max; // max distance captured during pre-arm checks + uint32_t last_reading_ms; // system time of last successful update from sensor AP_Int8 type; AP_Int8 pin; @@ -147,6 +148,7 @@ public: bool has_data_orient(enum Rotation orientation) const; uint8_t range_valid_count_orient(enum Rotation orientation) const; const Vector3f &get_pos_offset_orient(enum Rotation orientation) const; + uint32_t last_reading_ms(enum Rotation orientation) const; /* set an externally estimated terrain height. Used to enable power diff --git a/libraries/AP_RangeFinder/RangeFinder_Backend.h b/libraries/AP_RangeFinder/RangeFinder_Backend.h index 32da7e8f49..2be2caad1a 100644 --- a/libraries/AP_RangeFinder/RangeFinder_Backend.h +++ b/libraries/AP_RangeFinder/RangeFinder_Backend.h @@ -55,6 +55,9 @@ public: // in metres relative to the body frame origin const Vector3f &get_pos_offset() const { return state.pos_offset; } + // return system time of last successful read from the sensor (used for DPTH logging) + uint32_t last_reading_ms() const { return state.last_reading_ms; } + protected: // update status based on distance measurement