1
$\begingroup$

I am trying publish the pose of the camera and view it in rviz2. I am using ros2 Humble and gazebo fortress. I can see the image using the image topic but i am not able to visualize the topic in the gazebo as well. Here is my sdf file.

<?xml version="1.0" ?> <sdf version="1.6"> <world name="test"> <plugin filename="ignition-gazebo-physics-system" name="gz::sim::systems::Physics"> </plugin> <plugin filename="ignition-gazebo-sensors-system" name="gz::sim::systems::Sensors"> <render_engine>ogre2</render_engine> </plugin> <plugin filename="ignition-gazebo-user-commands-system" name="gz::sim::systems::UserCommands"> </plugin> <plugin filename="ignition-gazebo-scene-broadcaster-system" name="gz::sim::systems::SceneBroadcaster"> </plugin> <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 0.0 1</normal> <size>100 100</size> </plane> </geometry> </collision> <visual name="visual"> <geometry> <plane> <normal>0.0 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> <model name="box"> <pose>5.0 0 0.7 0 0 0</pose> <link name="box_link"> <inertial> <inertia> <ixx>1</ixx> <ixy>0</ixy> <ixz>0</ixz> <iyy>1</iyy> <iyz>0</iyz> <izz>1</izz> </inertia> <mass>1.0</mass> </inertial> <collision name="box_collision"> <geometry> <box> <size>1 1 1</size> </box> </geometry> </collision> <visual name="box_visual"> <geometry> <box> <size>1 1 1</size> </box> </geometry> <material> <ambient>0.3 0.3 0.3 1</ambient> <diffuse>0.3 0.3 0.3 1</diffuse> <specular>0.3 0.5 0.3 1</specular> </material> </visual> </link> </model> <model name="model_with_camera"> <static>true</static> <pose>4 -6 2 0 0 1.57</pose> <link name="link"> <pose>0.05 0.05 0.05 0 0 0</pose> <visual name="visual"> <geometry> <box> <size>0.1 0.1 0.1</size> </box> </geometry> </visual> <sensor name="camera" type="camera"> <camera> <horizontal_fov>1.047</horizontal_fov> <image> <width>640</width> <height>480</height> </image> <clip> <near>0.1</near> <far>100</far> </clip> </camera> <always_on>1</always_on> <update_rate>30</update_rate> <visualize>true</visualize> <topic>camera</topic> </sensor> </link> </model> <model name="lidar"> <pose>4.05 -6 2 0 0 1.57</pose> <link name="link"> <pose>0.05 0.05 0.05 0 0 0</pose> <inertial> <mass>0.1</mass> <inertia> <ixx>0.000166667</ixx> <iyy>0.000166667</iyy> <izz>0.000166667</izz> </inertia> </inertial> <collision name="collision"> <geometry> <box> <size>0.1 0.1 0.1</size> </box> </geometry> </collision> <visual name="visual"> <geometry> <box> <size>0.1 0.1 0.1</size> </box> </geometry> </visual> <sensor name='gpu_lidar' type='gpu_lidar'> <topic>lidar</topic> <update_rate>10</update_rate> <lidar> <scan> <horizontal> <samples>1024</samples> <resolution>1</resolution> <min_angle>-1.396263</min_angle> <max_angle>1.396263</max_angle> </horizontal> <vertical> <samples>64</samples> <resolution>1</resolution> <min_angle>-0.261799</min_angle> <max_angle>0.261799</max_angle> </vertical> </scan> <range> <min>0.08</min> <max>30.0</max> <resolution>0.01</resolution> </range> </lidar> <alwaysOn>1</alwaysOn> <visualize>true</visualize> </sensor> <plugin filename="ignition-gazebo-pose-publisher-system" name="gz::sim::systems::PosePublisher"> <publish_link_pose>true</publish_link_pose> <publish_sensor_pose>true</publish_sensor_pose> <use_pose_vector_msg>true</use_pose_vector_msg> <static_publisher>true</static_publisher> </plugin> </link> <static>true</static> </model> </world> </sdf> 

I tried to publish the pose of the lidar using pose-publisher-system as well. Thank you.

$\endgroup$

1 Answer 1

2
$\begingroup$

A Gazebo Sim system plugin can only be attached to a <world>, a <model> or a <sensor>, not to a <link>. You should be getting an error message for this in the log output, I think even without verbose output enabled. In any case: for testing purposes it is advisable to enable verbose output (-v 4), e.g.:

ign gazebo -v 4 world.sdf 

All standard Gazebo Fortress system plugins can be found in the GitHub repository. See the other branches of that repository for the other Gazebo Sim versions.

Each plugin has usage documentation in its header file. For the PosePublisher system see this part of the header file.

I haven't used that plugin yet, but given following documentation I conclude that you just have to add the plugin to the <model> in order to get all pose information published:

Attach to an entity to publish the transform of its child entities in the form of gz::msgs::Pose messages, or a single gz::msgs::Pose_V message if "use_pose_vector_msg" is true.

The GitHub repository also holds example worlds that show the use of each plugin. Here is the one for the pose publisher.

$\endgroup$
1
  • $\begingroup$ If you need the sensor pose too, don't forget to set <publish_sensor_pose>true</publish_sensor_pose> $\endgroup$ Commented Mar 24 at 0:36

Start asking to get answers

Find the answer to your question by asking.

Ask question

Explore related questions

See similar questions with these tags.