AP_Baro: allow setHIL to set last update time
This commit is contained in:
parent
1bf057be45
commit
8b7bf5cf7a
@ -246,7 +246,7 @@ float AP_Baro::get_air_density_ratio(void)
|
|||||||
// note that this relies on read() being called regularly to get new data
|
// note that this relies on read() being called regularly to get new data
|
||||||
float AP_Baro::get_climb_rate(void)
|
float AP_Baro::get_climb_rate(void)
|
||||||
{
|
{
|
||||||
if (_hil.have_crate) {
|
if (_hil.have_alt) {
|
||||||
return _hil.climb_rate;
|
return _hil.climb_rate;
|
||||||
}
|
}
|
||||||
// we use a 7 point derivative filter on the climb rate. This seems
|
// we use a 7 point derivative filter on the climb rate. This seems
|
||||||
@ -384,6 +384,9 @@ void AP_Baro::update(void)
|
|||||||
if (_hil.have_alt) {
|
if (_hil.have_alt) {
|
||||||
sensors[0].altitude = _hil.altitude;
|
sensors[0].altitude = _hil.altitude;
|
||||||
}
|
}
|
||||||
|
if (_hil.have_last_update) {
|
||||||
|
sensors[0].last_update_ms = _hil.last_update_ms;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// ensure the climb rate filter is updated
|
// ensure the climb rate filter is updated
|
||||||
|
@ -106,7 +106,7 @@ public:
|
|||||||
|
|
||||||
// HIL (and SITL) interface, setting pressure, temperature, altitude and climb_rate
|
// HIL (and SITL) interface, setting pressure, temperature, altitude and climb_rate
|
||||||
// used by Replay
|
// used by Replay
|
||||||
void setHIL(uint8_t instance, float pressure, float temperature, float altitude, float climb_rate);
|
void setHIL(uint8_t instance, float pressure, float temperature, float altitude, float climb_rate, uint32_t last_update_ms);
|
||||||
|
|
||||||
// HIL variables
|
// HIL variables
|
||||||
struct {
|
struct {
|
||||||
@ -114,9 +114,10 @@ public:
|
|||||||
float temperature;
|
float temperature;
|
||||||
float altitude;
|
float altitude;
|
||||||
float climb_rate;
|
float climb_rate;
|
||||||
|
uint32_t last_update_ms;
|
||||||
bool updated:1;
|
bool updated:1;
|
||||||
bool have_alt:1;
|
bool have_alt:1;
|
||||||
bool have_crate:1;
|
bool have_last_update:1;
|
||||||
} _hil;
|
} _hil;
|
||||||
|
|
||||||
// register a new sensor, claiming a sensor slot. If we are out of
|
// register a new sensor, claiming a sensor slot. If we are out of
|
||||||
|
@ -62,7 +62,7 @@ void AP_Baro::setHIL(float altitude_msl)
|
|||||||
/*
|
/*
|
||||||
set HIL pressure and temperature for an instance
|
set HIL pressure and temperature for an instance
|
||||||
*/
|
*/
|
||||||
void AP_Baro::setHIL(uint8_t instance, float pressure, float temperature, float altitude, float climb_rate)
|
void AP_Baro::setHIL(uint8_t instance, float pressure, float temperature, float altitude, float climb_rate, uint32_t last_update_ms)
|
||||||
{
|
{
|
||||||
if (instance >= _num_sensors) {
|
if (instance >= _num_sensors) {
|
||||||
// invalid
|
// invalid
|
||||||
@ -74,7 +74,11 @@ void AP_Baro::setHIL(uint8_t instance, float pressure, float temperature, float
|
|||||||
_hil.climb_rate = climb_rate;
|
_hil.climb_rate = climb_rate;
|
||||||
_hil.updated = true;
|
_hil.updated = true;
|
||||||
_hil.have_alt = true;
|
_hil.have_alt = true;
|
||||||
_hil.have_crate = true;
|
|
||||||
|
if (last_update_ms != 0) {
|
||||||
|
_hil.last_update_ms = last_update_ms;
|
||||||
|
_hil.have_last_update = true;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Read the sensor
|
// Read the sensor
|
||||||
|
Loading…
Reference in New Issue
Block a user