IMU topics not being published from X3 UAV model
I am trying to run the X3 UAV model using ignition gazebo. However, After spawning the vehicle, the imu topics are not being publsihed. The world file is as the following, which comes from https://github.com/ignitionrobotics/ign-gazebo/blob/master/examples/worlds/quadcopter.sdf
<?xml version="1.0" ?>
<sdf version="1.6">
<world name="quadcopter">
<physics name="4ms" type="ignored">
<max_step_size>0.004</max_step_size>
<real_time_factor>1.0</real_time_factor>
</physics>
<plugin
filename="libignition-gazebo-physics-system.so"
name="ignition::gazebo::systems::Physics">
</plugin>
<plugin
filename="libignition-gazebo-scene-broadcaster-system.so"
name="ignition::gazebo::systems::SceneBroadcaster">
</plugin>
<plugin
filename="libignition-gazebo-user-commands-system.so"
name="ignition::gazebo::systems::UserCommands">
</plugin>
<plugin
filename="libignition-gazebo-sensors-system.so"
name="ignition::gazebo::systems::Sensors">
<render_engine>ogre2</render_engine>
</plugin>
<gui fullscreen="0">
<!-- 3D scene -->
<plugin filename="GzScene3D" name="3D View">
<ignition-gui>
<title>3D View</title>
<property type="bool" key="showTitleBar">false</property>
<property type="string" key="state">docked</property>
</ignition-gui>
<engine>ogre2</engine>
<scene>scene</scene>
<ambient_light>0.4 0.4 0.4</ambient_light>
<background_color>0.8 0.8 0.8</background_color>
<camera_pose>-6 0 6 0 0.5 0</camera_pose>
</plugin>
<!-- World control -->
<plugin filename="WorldControl" name="World control">
<ignition-gui>
<title>World control</title>
<property type="bool" key="showTitleBar">false</property>
<property type="bool" key="resizable">false</property>
<property type="double" key="height">72</property>
<property type="double" key="width">121</property>
<property type="double" key="z">1</property>
<property type="string" key="state">floating</property>
<anchors target="3D View">
<line own="left" target="left"/>
<line own="bottom" target="bottom"/>
</anchors>
</ignition-gui>
<play_pause>true</play_pause>
<step>true</step>
<start_paused>true</start_paused>
<service>/world/quadcopter/control</service>
<stats_topic>/world/quadcopter/stats</stats_topic>
</plugin>
<!-- World statistics -->
<plugin filename="WorldStats" name="World stats">
<ignition-gui>
<title>World stats</title>
<property type="bool" key="showTitleBar">false</property>
<property type="bool" key="resizable">false</property>
<property type="double" key="height">110</property>
<property type="double" key="width">290</property>
<property type="double" key="z">1</property>
<property type="string" key="state">floating</property>
<anchors target="3D View">
<line own="right" target="right"/>
<line own="bottom" target="bottom"/>
</anchors>
</ignition-gui>
<sim_time>true</sim_time>
<real_time>true</real_time>
<real_time_factor>true</real_time_factor>
<iterations>true</iterations>
<topic>/world/quadcopter/stats</topic>
</plugin>
</gui>
<light type="directional" name="sun">
<cast_shadows>true</cast_shadows>
<pose>0 0 10 0 0 0</pose>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.2 0.2 0.2 1</specular>
<attenuation>
<range>1000</range>
<constant>0.9</constant>
<linear>0.01</linear>
<quadratic>0.001</quadratic>
</attenuation>
<direction>-0.5 0.1 -0.9</direction>
</light>
<model name="ground_plane">
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<plane>
<normal>0 0 1</normal>
</plane>
</geometry>
</collision>
<visual name="visual">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
<material>
<ambient>0.8 0.8 0.8 1</ambient>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.8 0.8 0.8 1</specular>
</material>
</visual>
</link>
</model>
<include>
<uri>
https://fuel.ignitionrobotics.org/1.0/nate/models/x3_description
</uri>
</include>
</world>
</sdf>
The out put of the topic list is as the following.
$ ign topic -l
/clock
/stats
/world/quadcopter/clock
/world/quadcopter/dynamic_pose/info
/world/quadcopter/model/X3/link/base_link/sensor/bottom_laser/scan
/world/quadcopter/model/X3/link/base_link/sensor/bottom_laser/scan/points
/world/quadcopter/model/X3/link/base_link/sensor/camera_front/camera_info
/world/quadcopter/model/X3/link/base_link/sensor/camera_front/depth_image
/world/quadcopter/model/X3/link/base_link/sensor/camera_front/image
/world/quadcopter/model/X3/link/base_link/sensor/camera_front/points
/world/quadcopter/model/X3/link/base_link/sensor/top_laser/scan
/world/quadcopter/model/X3/link/base_link/sensor/top_laser/scan/points
/world/quadcopter/pose/info
/world/quadcopter/scene/deletion
/world/quadcopter/scene/info
/world/quadcopter/state
/world/quadcopter/stats
Where it doesn't seem to include imu topics. This is a bit strange because I can see the model includes a imu plugin. Do I need to enable something so that the imu sensor publishes topics? or how can I subscribe to the imu information if it is not publishing topics?
Asked by Jaeyoung-Lim on 2020-05-31 07:56:09 UTC
Answers
The model contains the <sensor>
tag, but at the moment, ign-gazebo requires you to add the IMU system to the <world>
tag in the SDFormat file like so:
<plugin
filename="libignition-gazebo-imu-system.so"
name="ignition::gazebo::systems::Imu">
</plugin>
Asked by azeey on 2020-06-01 10:59:24 UTC
Comments