mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-25 00:31:36 +08:00
simulator: fix conversion from hPa to Pa
Signed-off-by: RomanBapst <bapstroman@gmail.com>
This commit is contained in:
@@ -161,6 +161,8 @@ private:
|
||||
|
||||
static Simulator *_instance;
|
||||
|
||||
static constexpr float hPa2Pa = 100.0f; // hectopascal to pascal multiplier
|
||||
|
||||
// simulated sensor instances
|
||||
static constexpr uint8_t ACCEL_COUNT_MAX = 3;
|
||||
PX4Accelerometer _px4_accel[ACCEL_COUNT_MAX] {
|
||||
|
||||
@@ -328,7 +328,7 @@ void Simulator::update_sensors(const hrt_abstime &time, const mavlink_hil_sensor
|
||||
if ((sensors.fields_updated & SensorSource::BARO) == SensorSource::BARO && !_baro_blocked) {
|
||||
|
||||
if (!_baro_stuck) {
|
||||
_last_baro_pressure = sensors.abs_pressure;
|
||||
_last_baro_pressure = sensors.abs_pressure * hPa2Pa; // convert hPa to Pa
|
||||
_last_baro_temperature = sensors.temperature;
|
||||
}
|
||||
|
||||
@@ -354,8 +354,8 @@ void Simulator::update_sensors(const hrt_abstime &time, const mavlink_hil_sensor
|
||||
differential_pressure_s report{};
|
||||
report.timestamp = time;
|
||||
report.temperature = _sensors_temperature;
|
||||
report.differential_pressure_filtered_pa = sensors.diff_pressure * 100.0f; // convert from millibar to bar;
|
||||
report.differential_pressure_raw_pa = sensors.diff_pressure * 100.0f; // convert from millibar to bar;
|
||||
report.differential_pressure_filtered_pa = sensors.diff_pressure * hPa2Pa; // convert hPa to Pa;
|
||||
report.differential_pressure_raw_pa = sensors.diff_pressure * hPa2Pa; // convert hPa to Pa;
|
||||
|
||||
_differential_pressure_pub.publish(report);
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user