Failed to create a bridge for topic when done using ROS2 python launch file but works using command line
Hi,
I am using ROS2 Humble Hawksbill on Ubuntu 22.04 Jammy along with Ignition Fortress which comes pre-packed with the desktop-full variant of ROS for amd64 architecture.
I have an sdf file which contains both robot (with lidar sensor) and the environment. IGN gazebo publishes two topics: one for laserscan(ignition.msgs.LaserScan in IGN or sensormsgs/msg/LaserScan in ROS2) and second for point cloud2 (ignition.msgs.PointCloudPacked in IGN or sensor_msgs/msg/PointCloud2 in ROS).
After loading the model in ign gazebo and running the simulation, I was able to create a rosignbridge for the above two topics and remapped them the using command line which works perfectly. I can echo the messages and see visualization on rviz2 as well.
ros2 run rosignbridge parameterbridge /lidar2@sensormsgs/msg/LaserScan[ignition.msgs.LaserScan --ros-args -r /lidar2:=/laser_scan
ros2 run rosignbridge parameterbridge /lidar2/points@sensormsgs/msg/PointCloud2[ignition.msgs.PointCloudPacked --ros-args -r /lidar2/points:=/point_cloud2
But the problem occurs when I try to do so using a python launch file. It can load load the model and start the simulation in ign, but can not create a bridge properly. "ros2 topic list" shows below which indicates that the bridge is working (at least partially).
/clickedpoint /goalpose /initialpose /laserscan /model/vehicleblue/cmdvel /parameterevents /pointcloud2 /rosout /tf /tfstatic
Then, I did "ros2 topic echo /laserscan" or "ros2 topic echo /pointcloud2" topics which gives below error.
2022-06-17 17:42:00.940 [RTPSTRANSPORTSHM Error] Failed initport fastrtpsport7427: openandlockfile failed -> Function openport_internal
However, "ign topic -e -t /lidar2" and "ign topic -e -t /lidar2/points" shows data indicating that the sensors are spitting out values but the bridge is not working correctly.
Below is my launch file: C:\fakepath\spawnhuskylaunch.py
and here is the error output on terminal:
[INFO] [launch]: All log files can be found below /home/dev/.ros/log/2022-06-17-17-35-05-870954-dev-Aspire-A715-75G-3546281 [INFO] [launch]: Default logging verbosity is set to INFO [INFO] [ign gazebo-1]: process started with pid [3546292] [INFO] [rviz2-2]: process started with pid [3546295] [rviz2-2] [INFO] [1655501707.397163518] [rviz2]: Stereo is NOT SUPPORTED [rviz2-2] [INFO] [1655501707.397227733] [rviz2]: OpenGl version: 4.6 (GLSL 4.6) [rviz2-2] [INFO] [1655501707.417738708] [rviz2]: Stereo is NOT SUPPORTED [ign gazebo-1] [Err] [SystemPaths.cc:467] Could not resolve file [playgrounddiffuse.jpg] [ign gazebo-1] libEGL warning: DRI2: failed to create dri screen [ign gazebo-1] libEGL warning: DRI2: failed to create dri screen [ign gazebo-1] [Err] [SystemPaths.cc:467] Could not resolve file [playground_diffuse.jpg] [ign gazebo-1] libEGL warning: DRI2: failed to create dri screen [ign gazebo-1] libEGL warning: DRI2: failed to create dri screen [ign gazebo-1] [GUI] [Err] [SystemPaths.cc:467] Could not resolve file [playgrounddiffuse.jpg] [INFO] [parameterbridge-3]: process started with pid [3550288] [parameter_bridge-3] 2022-06-17 17:35:17.253 [RTPSTRANSPORTSHM Error] Failed initport fastrtpsport7427: openandlockfile failed -> Function openportinternal [parameterbridge-3] Failed to create a bridge for topic [/lidar2] with ROS2 type [sensormsgs/msg/LaserScan] and Ignition Transport type [ignition.msgs.LaserScan --ros-args -r /lidar2:=/laserscan] [parameterbridge-3] Failed to create a bridge for topic [/lidar2/points] with ROS2 type [sensormsgs/msg/PointCloud2] and Ignition Transport type [ignition.msgs.PointCloudPacked --ros-args -r /lidar2/points:=/pointcloud2]
Initially, in the launch file, inside of "return LaunchDescription", "bridge" was present instead of "TimerAction(period=10.0,actions=[bridge])" which gave the same error. Then, I thought that the computer might be loading the model and then creating the bridge very fast (even before the sensor start to send data), so, having a delay would be better but it still did not work out.
Can anyone please suggest what is the issue over here?
Thanks,
Dev
Asked by devvaibhav on 2022-06-17 16:48:04 UTC
Comments