Fix for sensor airspeed enable.

Signed-off-by: Benjamin Perseghetti <bperseghetti@rudislabs.com>
This commit is contained in:
Benjamin Perseghetti 2023-01-25 12:20:32 -05:00
parent 90d904bfd4
commit 29e1e0df91
No known key found for this signature in database
GPG Key ID: B2B0FDB44D2F831F
6 changed files with 16 additions and 32 deletions

View File

@ -49,7 +49,7 @@ elif [ "$PX4_SIMULATOR" = "gz" ] || [ "$(param show -q SIM_GZ_EN)" -eq "1" ]; th
echo "INFO [init] starting gazebo with world: ${PX4_GZ_WORLDS}/${PX4_GZ_WORLD}.sdf"
${gz_command} ${gz_sub_command} --verbose=1 -r -s "${PX4_GZ_WORLDS}/${PX4_GZ_WORLD}.sdf" &
${gz_command} ${gz_sub_command} --verbose=4 -r -s "${PX4_GZ_WORLDS}/${PX4_GZ_WORLD}.sdf" &
if [ -z "${HEADLESS}" ]; then
# HEADLESS not set, starting gui

View File

@ -135,7 +135,7 @@
<update_rate>250</update_rate>
</sensor>
</link>
<link name="airspeed">
<link name="airspeed_link">
<pose>0 0 0 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
@ -177,23 +177,9 @@
</sensor>
</link>
<joint name='airspeed_joint' type='fixed'>
<child>airspeed</child>
<child>airspeed_link</child>
<parent>base_link</parent>
</joint>
<!-- <include>
<uri>model://airspeed</uri>
<pose>0 0 0 0 0 0</pose>
<name>airspeed</name>
</include>
<include>
<uri>model://magnetometer</uri>
<pose>0 0 0 0 0 0</pose>
<name>mag</name>
</include>
<joint name='mag_joint' type='fixed'>
<child>mag::link</child>
<parent>base_link</parent>
</joint> -->
<link name='rotor_0'>
<pose>0.35 -0.35 0.07 0 0 0</pose>
<inertial>

View File

@ -5,12 +5,12 @@
<real_time_factor>1.0</real_time_factor>
<real_time_update_rate>250</real_time_update_rate>
</physics>
<plugin name='ignition::gazebo::systems::Physics' filename='ignition-gazebo-physics-system'/>
<plugin name='ignition::gazebo::systems::UserCommands' filename='ignition-gazebo-user-commands-system'/>
<plugin name='ignition::gazebo::systems::SceneBroadcaster' filename='ignition-gazebo-scene-broadcaster-system'/>
<plugin name='ignition::gazebo::systems::Contact' filename='ignition-gazebo-contact-system'/>
<plugin name='ignition::gazebo::systems::Imu' filename='ignition-gazebo-imu-system'/>
<plugin name='ignition::gazebo::systems::Sensors' filename='ignition-gazebo-sensors-system'>
<plugin name='gz::sim::systems::Physics' filename='gz-sim-physics-system'/>
<plugin name='gz::sim::systems::UserCommands' filename='gz-sim-user-commands-system'/>
<plugin name='gz::sim::systems::SceneBroadcaster' filename='gz-sim-scene-broadcaster-system'/>
<plugin name='gz::sim::systems::Contact' filename='gz-sim-contact-system'/>
<plugin name='gz::sim::systems::Imu' filename='gz-sim-imu-system'/>
<plugin name='gz::sim::systems::Sensors' filename='gz-sim-sensors-system'>
<render_engine>ogre2</render_engine>
</plugin>
<gui fullscreen='false'>

View File

@ -35,7 +35,6 @@
find_package(gz-transport
#REQUIRED COMPONENTS core
NAMES
#ignition-transport11 # IGN (Fortress and earlier) no longer supported
gz-transport12
#QUIET
)

View File

@ -152,7 +152,7 @@ int GZBridge::init()
return PX4_ERROR;
}
#if 0
// Airspeed: /world/$WORLD/model/$MODEL/link/airspeed_link/sensor/air_speed/air_speed
std::string airpressure_topic = "/world/" + _world_name + "/model/" + _model_name +
"/link/airspeed_link/sensor/air_speed/air_speed";
@ -162,7 +162,6 @@ int GZBridge::init()
return PX4_ERROR;
}
#endif
if (!_mixing_interface_esc.init(_model_name)) {
PX4_ERR("failed to init ESC output");
@ -329,14 +328,14 @@ void GZBridge::clockCallback(const gz::msgs::Clock &clock)
pthread_mutex_unlock(&_node_mutex);
}
#if 0
void GZBridge::airpressureCallback(const gz::msgs::FluidPressure &air_pressure)
{
if (hrt_absolute_time() == 0) {
return;
}
pthread_mutex_lock(&_mutex);
pthread_mutex_lock(&_node_mutex);
const uint64_t time_us = (air_pressure.header().stamp().sec() * 1000000)
+ (air_pressure.header().stamp().nsec() / 1000);
@ -353,7 +352,7 @@ void GZBridge::airpressureCallback(const gz::msgs::FluidPressure &air_pressure)
pthread_mutex_unlock(&_node_mutex);
}
#endif
void GZBridge::imuCallback(const gz::msgs::IMU &imu)
{

View File

@ -59,7 +59,7 @@
#include <gz/msgs.hh>
#include <gz/transport.hh>
// #include <gz/msgs/fluid_pressure.pb.h>
#include <gz/msgs/fluid_pressure.pb.h>
#include <gz/msgs/imu.pb.h>
using namespace time_literals;
@ -94,14 +94,14 @@ private:
void clockCallback(const gz::msgs::Clock &clock);
//void airpressureCallback(const gz::msgs::FluidPressure &air_pressure);
void airpressureCallback(const gz::msgs::FluidPressure &air_pressure);
void imuCallback(const gz::msgs::IMU &imu);
void poseInfoCallback(const gz::msgs::Pose_V &pose);
// Subscriptions
uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s};
//uORB::Publication<differential_pressure_s> _differential_pressure_pub{ORB_ID(differential_pressure)};
uORB::Publication<differential_pressure_s> _differential_pressure_pub{ORB_ID(differential_pressure)};
uORB::Publication<vehicle_angular_velocity_s> _angular_velocity_ground_truth_pub{ORB_ID(vehicle_angular_velocity_groundtruth)};
uORB::Publication<vehicle_attitude_s> _attitude_ground_truth_pub{ORB_ID(vehicle_attitude_groundtruth)};
uORB::Publication<vehicle_global_position_s> _gpos_ground_truth_pub{ORB_ID(vehicle_global_position_groundtruth)};