-
Notifications
You must be signed in to change notification settings - Fork 225
Description
Bug report
Required Info:
- Operating System:
- Ubuntu 22.04
- Installation type:
- Binaries
- Version or commit hash:
- 0.25.5-1jammy.20231117.203705
- DDS implementation:
- Humble default
- Client library (if applicable):
- rclcpp
Steps to reproduce issue
- Compile the project CARLA ROS bridge
- Load the
rviz_carla_plugin - Publish any message from CARLA
Expected behavior
Rviz2 should load the plugin and process the messages as intended
Actual behavior
Rviz2 crashes with the message:
rviz2: symbol lookup error: /home/felipe/Documents/Github/carla_ws/install/rviz_carla_plugin/lib/librviz_carla_plugin.so: undefined symbol: _ZN3tf27fromMsgERKN13geometry_msgs3msg11Quaternion_ISaIvEEERNS_10QuaternionEAdditional information
There is a lot of stuff going on in this setup, so it wasn't easy to pin point the problem within geometry2.
The evidence that I collected so far, in the file tf2/impl/utils.h, we have the declaration of the prototype fromMsg function.
geometry2/tf2/include/tf2/impl/utils.h
Line 29 in b9b06ec
| void fromMsg(const geometry_msgs::msg::Quaternion & in, tf2::Quaternion & out); |
This declaration creates an undefined symbol in the plugin dynamic object.
$ objdump -tC ./build/rviz_carla_plugin/CMakeFiles/rviz_carla_plugin.dir/src/carla_control_panel_ROS2.cpp.o | grep fromMsg
0000000000000000 *UND* 0000000000000000 tf2::fromMsg(geometry_msgs::msg::Quaternion_<std::allocator<void> > const&, tf2::Quaternion&)When rviz2 tries to execute the plugin's code, it stumbles upon an undefined symbol and then crashes.
As described here carla-simulator/ros-bridge#711, a quick and dirt solution is to add a bogus fromMsg declaration
namespace tf2{
void fromMsg(const geometry_msgs::msg::Quaternion & in, tf2::Quaternion & out){
(void)(in);
(void)(out);
};
}I tried to include tf2/convert.h and call the template version of fromMsg, but I got a different error
Code in rviz2 plugin
namespace tf2{
void fromMsg(const geometry_msgs::msg::Quaternion & in, tf2::Quaternion & out){
fromMsg(in, out);
};
}Terminal
rviz2 -d src/ros-bridge/carla_ad_demo/config/carla_ad_demo_ros2
.rviz
[INFO] [1701717747.297741667] [rviz2]: Stereo is NOT SUPPORTED
[INFO] [1701717747.297844785] [rviz2]: OpenGl version: 4.6 (GLSL 4.6)
[INFO] [1701717747.323646353] [rviz2]: Stereo is NOT SUPPORTED
fish: Job 1, 'rviz2 -d src/ros-bridge/carla_a…' terminated by signal SIGSEGV (Address boundary error)I'm not sure why the prototype declaration of the fromMsg is needed, so my suggestion would be the simple removal of that declaration in that file.
It may be related to #242, but I'm not entirely sure