gazebo ros camera plugin fail with segmentation fault ?
Hello,
I'm trying to run a simulation with ROS2 foxy + Gazebo 11 on Ubuntu 20.04. I'm able to run gazebo simulations and controlling it from ROS2 nodes as soon as I do not have a camera.
With a camera, I tried several worlds, using or not the ROS2 launch files and finally, I would say my minimally failing example is running
fix_jer@stollen:~/ros2_foxy$ gzserver /opt/ros/foxy/share/gazebo_plugins/worlds/gazebo_ros_camera_demo.world --verbose -s libgazebo_ros_init.so -s libgazebo_ros_factory.so -s libgazebo_ros_force_system.so -s libgazebo_ros_camera.so
Gazebo multi-robot simulator, version 11.11.0
Copyright (C) 2012 Open Source Robotics Foundation.
Released under the Apache 2 License.
http://gazebosim.org
[Err] [gazebo_shared.cc:46] System is attempting to load a plugin, but detected an incorrect plugin type. Plugin filename[libgazebo_ros_camera.so].
[Msg] Waiting for master.
[Msg] Connected to gazebo master @ http://127.0.0.1:11345
[Msg] Publicized address: 192.168.1.84
[Msg] Loading world file [/opt/ros/foxy/share/gazebo_plugins/worlds/gazebo_ros_camera_demo.world]
Segmentation fault (core dumped)
The last plugin load -s libgazebo_ros_camera.so
, I added it as I thought it might be necessary but the execution is failing with or without it.
If I try running it with gdb , the backtrace gives :
Thread 1 "gzserver" received signal SIGSEGV, Segmentation fault.
0x0000555555563fbe in std::_Sp_counted_base<(__gnu_cxx::_Lock_policy)2>::_M_release() ()
(gdb) bt
#0 0x0000555555563fbe in std::_Sp_counted_base<(__gnu_cxx::_Lock_policy)2>::_M_release() ()
#1 0x00007fffde475e4a in rclcpp::PublisherOptionsWithAllocator<std::allocator<void> >::~PublisherOptionsWithAllocator() () at /opt/ros/foxy/lib/libgazebo_ros_init.so
#2 0x00007fff42eef635 in std::_Function_base::_Base_manager<rclcpp::create_publisher_factory<sensor_msgs::msg::Image_<std::allocator<void> >, std::allocator<void>, rclcpp::Publisher<sensor_msgs::msg::Image_<std::allocator<void> >, std::allocator<void> > >(rclcpp::PublisherOptionsWithAllocator<std::allocator<void> > const&)::{lambda(rclcpp::node_interfaces::NodeBaseInterface*, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&)#1}>::_M_manager(std::_Any_data&, std::_Any_data const&, std::_Manager_operation) () at /opt/ros/foxy/lib/libimage_transport_plugins.so
#3 0x00007fff42eeeb1b in std::shared_ptr<rclcpp::Publisher<sensor_msgs::msg::Image_<std::allocator<void> >, std::allocator<void> > > rclcpp::create_publisher<sensor_msgs::msg::Image_<std::allocator<void> >, std::allocator<void>, rclcpp::Publisher<sensor_msgs::msg::Image_<std::allocator<void> >, std::allocator<void> >, rclcpp::Node>(rclcpp::Node&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&, rclcpp::PublisherOptionsWithAllocator<std::allocator<void> > const&) () at /opt/ros/foxy/lib/libimage_transport_plugins.so
#4 0x00007fff42eeef64 in image_transport::SimplePublisherPlugin<sensor_msgs::msg::Image_<std::allocator<void> > >::advertiseImpl(rclcpp::Node*, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rmw_qos_profile_t) () at /opt/ros/foxy/lib/libimage_transport_plugins.so
#5 0x00007fff49762d3a in image_transport::Publisher::Publisher(rclcpp::Node*, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, std::shared_ptr<pluginlib::ClassLoader<image_transport::PublisherPlugin> >, rmw_qos_profile_t) () at /opt/ros/foxy/lib/libimage_transport.so
#6 0x00007fff49797922 in image_transport::create_publisher(rclcpp::Node*, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rmw_qos_profile_t) ()
at /opt/ros/foxy/lib/libimage_transport.so
#7 0x00007fff60152b83 in gazebo_plugins::GazeboRosCamera::Load(std::shared_ptr<gazebo::sensors::Sensor>, std::shared_ptr<sdf::v9::Element>) () at /opt/ros/foxy/lib/libgazebo_ros_camera.so
#8 0x00007ffff728d698 in gazebo::sensors::Sensor::LoadPlugin(std::shared_ptr<sdf::v9::Element>) () at /lib/x86_64-linux-gnu/libgazebo_sensors.so.11
#9 0x00007ffff728dac8 in gazebo::sensors::Sensor::Init() () at /lib/x86_64-linux-gnu/libgazebo_sensors.so.11
#10 0x00007ffff72577a3 in gazebo::sensors::CameraSensor::Init() () at /lib/x86_64-linux-gnu/libgazebo_sensors.so.11
#11 0x00007ffff7298700 in gazebo::sensors::SensorManager::Update(bool) () at /lib/x86_64-linux-gnu/libgazebo_sensors.so.11
#12 0x00007ffff7f1c80f in gazebo::Server::Run() () at /lib/x86_64-linux-gnu/libgazebo.so.11
#13 0x00005555555625dd in ()
#14 0x00007ffff731f083 in __libc_start_main (main=0x5555555624e0, argc=9, argv=0x7fffffffcf38, init=<optimized out>, fini=<optimized out>, rtld_fini=<optimized out>, stack_end=0x7fffffffcf28)
at ../csu/libc-start.c:308
#15 0x00005555555626de in ()
Do you have any idea on where might be the problem ?
Thank you for your help; Best;
Jeremy.
Asked by jeremyfix on 2023-07-02 02:06:57 UTC
Comments