mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-02 05:04:08 +08:00
simulation/gz_bridge: use airspeed sensor msgs (#21060)
Signed-off-by: Alejandro Hernández Cordero <ahcorde@gmail.com>
This commit is contained in:
parent
f5389654c2
commit
f74d67920b
@ -330,7 +330,7 @@ void GZBridge::clockCallback(const gz::msgs::Clock &clock)
|
||||
}
|
||||
|
||||
|
||||
void GZBridge::airpressureCallback(const gz::msgs::FluidPressure &air_pressure)
|
||||
void GZBridge::airpressureCallback(const gz::msgs::AirSpeedSensor &air_pressure)
|
||||
{
|
||||
if (hrt_absolute_time() == 0) {
|
||||
return;
|
||||
@ -341,13 +341,13 @@ void GZBridge::airpressureCallback(const gz::msgs::FluidPressure &air_pressure)
|
||||
const uint64_t time_us = (air_pressure.header().stamp().sec() * 1000000)
|
||||
+ (air_pressure.header().stamp().nsec() / 1000);
|
||||
|
||||
double air_pressure_value = air_pressure.pressure();
|
||||
double air_pressure_value = air_pressure.diff_pressure();
|
||||
|
||||
differential_pressure_s report{};
|
||||
report.timestamp_sample = time_us;
|
||||
report.device_id = 1377548; // 1377548: DRV_DIFF_PRESS_DEVTYPE_SIM, BUS: 1, ADDR: 5, TYPE: SIMULATION
|
||||
report.differential_pressure_pa = static_cast<float>(air_pressure_value); // hPa to Pa;
|
||||
report.temperature = static_cast<float>(air_pressure.variance()) + CONSTANTS_ABSOLUTE_NULL_CELSIUS; // K to C
|
||||
report.temperature = static_cast<float>(air_pressure.temperature()) + CONSTANTS_ABSOLUTE_NULL_CELSIUS; // K to C
|
||||
report.timestamp = hrt_absolute_time();;
|
||||
_differential_pressure_pub.publish(report);
|
||||
|
||||
|
||||
@ -59,7 +59,7 @@
|
||||
#include <gz/msgs.hh>
|
||||
#include <gz/transport.hh>
|
||||
|
||||
#include <gz/msgs/fluid_pressure.pb.h>
|
||||
#include <gz/msgs/air_speed_sensor.pb.h>
|
||||
#include <gz/msgs/imu.pb.h>
|
||||
|
||||
using namespace time_literals;
|
||||
@ -94,7 +94,7 @@ private:
|
||||
|
||||
void clockCallback(const gz::msgs::Clock &clock);
|
||||
|
||||
void airpressureCallback(const gz::msgs::FluidPressure &air_pressure);
|
||||
void airpressureCallback(const gz::msgs::AirSpeedSensor &air_pressure);
|
||||
void imuCallback(const gz::msgs::IMU &imu);
|
||||
void poseInfoCallback(const gz::msgs::Pose_V &pose);
|
||||
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user