Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Segfault creating a publisher in MoveIt 2 Example, only with Fast DDS RMW #1118

Closed
sea-bass opened this issue Nov 9, 2023 · 7 comments
Closed

Comments

@sea-bass
Copy link

sea-bass commented Nov 9, 2023

Bug report

Required Info:

  • Operating System:
    • Ubuntu 22.04
  • Installation type:
    • Binaries
  • Version or commit hash:
    • Rolling
  • DDS implementation:
    • Fast DDS
  • Client library (if applicable):
    • rclcpp

Steps to reproduce issue

We tried running some of our MoveIt Tutorials on the latest version of ROS 2 Rolling, and ran into a segfault creating a publisher that only occurs with Fast DDS as the middleware -- switching to Cyclone DDS resolves the issue.

Our code snippet that fails is:

display_path_ =
      context_->moveit_cpp_->getNode()->create_publisher<moveit_msgs::msg::DisplayTrajectory>(DISPLAY_PATH_TOPIC, 10);

where the segfault is:

[move_group-4] terminate called after throwing an instance of 'rclcpp::exceptions::RCLError'
[move_group-4]   what():  could not create publisher: create_publisher() called for existing topic name rt/display_planned_path with incompatible type moveit_msgs::msg::dds_::DisplayTrajectory_, at ./src/publisher.cpp:145, at ./src/rcl/publisher.c:117
[move_group-4] Stack trace (most recent call last):
[move_group-4] #22   Object "", at 0xffffffffffffffff, in 
[move_group-4] #21   Object "/home/sebastian/workspace/moveit_ws/install/moveit_ros_move_group/lib/moveit_ros_move_group/move_group", at 0x557090e89f04, in _start
[move_group-4] #20   Source "../csu/libc-start.c", line 392, in __libc_start_main_impl [0x7f98f8c29e3f]
[move_group-4] #19   Source "../sysdeps/nptl/libc_start_call_main.h", line 58, in __libc_start_call_main [0x7f98f8c29d8f]
[move_group-4] #18   Object "/home/sebastian/workspace/moveit_ws/install/moveit_ros_move_group/lib/moveit_ros_move_group/move_group", at 0x557090e890d3, in main
[move_group-4] #17   Object "/home/sebastian/workspace/moveit_ws/install/moveit_ros_planning/lib/libmoveit_cpp.so.2.8.0", at 0x7f98f9a5c496, in moveit_cpp::MoveItCpp::MoveItCpp(std::shared_ptr<rclcpp::Node> const&, moveit_cpp::MoveItCpp::Options const&)
[move_group-4] #16   Object "/home/sebastian/workspace/moveit_ws/install/moveit_ros_planning/lib/libmoveit_cpp.so.2.8.0", at 0x7f98f9a5b3fb, in moveit_cpp::MoveItCpp::loadPlanningPipelines(moveit_cpp::MoveItCpp::PlanningPipelineOptions const&)
[move_group-4] #15   Object "/home/sebastian/workspace/moveit_ws/install/moveit_ros_planning/lib/libmoveit_planning_pipeline_interfaces.so.2.8.0", at 0x7f98f92d8acf, in moveit::planning_pipeline_interfaces::createPlanningPipelineMap(std::vector<std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, std::allocator<std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > > > const&, std::shared_ptr<moveit::core::RobotModel const> const&, std::shared_ptr<rclcpp::Node> const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&)
[move_group-4] #14   Object "/home/sebastian/workspace/moveit_ws/install/moveit_ros_planning/lib/libmoveit_planning_pipeline.so.2.8.0", at 0x7f98f8ebb968, in planning_pipeline::PlanningPipeline::PlanningPipeline(std::shared_ptr<moveit::core::RobotModel const> const&, std::shared_ptr<rclcpp::Node> const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&)
[move_group-4] #13   Object "/home/sebastian/workspace/moveit_ws/install/moveit_ros_planning/lib/libmoveit_planning_pipeline.so.2.8.0", at 0x7f98f8ee76a7, in void planning_pipeline::loadPluginVector<planning_interface::PlanningResponseAdapter>(std::shared_ptr<rclcpp::Node> const&, std::unique_ptr<pluginlib::ClassLoader<planning_interface::PlanningResponseAdapter>, std::default_delete<pluginlib::ClassLoader<planning_interface::PlanningResponseAdapter> > > const&, std::vector<std::shared_ptr<planning_interface::PlanningResponseAdapter const>, std::allocator<std::shared_ptr<planning_interface::PlanningResponseAdapter const> > >&, std::vector<std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, std::allocator<std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > > > const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&)
[move_group-4] #12   Object "/home/sebastian/workspace/moveit_ws/install/moveit_ros_planning/lib/libmoveit_default_planning_response_adapter_plugins.so.2.8.0", at 0x7f98c37ab05d, in default_planning_response_adapters::DisplayMotionPath::initialize(std::shared_ptr<rclcpp::Node> const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&)
[move_group-4] #11   Object "/home/sebastian/workspace/moveit_ws/install/moveit_ros_planning/lib/libmoveit_default_planning_response_adapter_plugins.so.2.8.0", at 0x7f98c37a750d, in std::shared_ptr<rclcpp::Publisher<moveit_msgs::msg::DisplayTrajectory_<std::allocator<void> >, std::allocator<void> > > rclcpp::detail::create_publisher<moveit_msgs::msg::DisplayTrajectory_<std::allocator<void> >, std::allocator<void>, rclcpp::Publisher<moveit_msgs::msg::DisplayTrajectory_<std::allocator<void> >, std::allocator<void> >, rclcpp::Node, rclcpp::Node>(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&)
[move_group-4] #10   Object "/opt/ros/rolling/lib/librclcpp.so", at 0x7f98f954cb1b, in rclcpp::node_interfaces::NodeTopics::create_publisher(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::PublisherFactory const&, rclcpp::QoS const&)
[move_group-4] #9    Object "/home/sebastian/workspace/moveit_ws/install/moveit_ros_planning/lib/libmoveit_default_planning_response_adapter_plugins.so.2.8.0", at 0x7f98c37a6c3e, in std::_Function_handler<std::shared_ptr<rclcpp::PublisherBase> (rclcpp::node_interfaces::NodeBaseInterface*, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&), rclcpp::create_publisher_factory<moveit_msgs::msg::DisplayTrajectory_<std::allocator<void> >, std::allocator<void>, rclcpp::Publisher<moveit_msgs::msg::DisplayTrajectory_<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_invoke(std::_Any_data const&, rclcpp::node_interfaces::NodeBaseInterface*&&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&)
[move_group-4] #8    Object "/opt/ros/rolling/lib/librclcpp.so", at 0x7f98f95986cb, in rclcpp::PublisherBase::PublisherBase(rclcpp::node_interfaces::NodeBaseInterface*, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rosidl_message_type_support_t const&, rcl_publisher_options_s const&, rclcpp::PublisherEventCallbacks const&, bool)
[move_group-4] #7    Object "/opt/ros/rolling/lib/librclcpp.so", at 0x7f98f94fe6d8, in rclcpp::exceptions::throw_from_rcl_error(int, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rcutils_error_state_s const*, void (*)())
[move_group-4] #6    Object "/usr/lib/x86_64-linux-gnu/libstdc++.so.6.0.30", at 0x7f98f90ae1fd, in std::rethrow_exception(std::__exception_ptr::exception_ptr)
[move_group-4] #5    Object "/usr/lib/x86_64-linux-gnu/libstdc++.so.6.0.30", at 0x7f98f90ae276, in std::terminate()
[move_group-4] #4    Object "/usr/lib/x86_64-linux-gnu/libstdc++.so.6.0.30", at 0x7f98f90ae20b, in 
[move_group-4] #3    Object "/usr/lib/x86_64-linux-gnu/libstdc++.so.6.0.30", at 0x7f98f90a2b9d, in 
[move_group-4] #2    Source "./stdlib/abort.c", line 79, in abort [0x7f98f8c287f2]
[move_group-4] #1    Source "../sysdeps/posix/raise.c", line 26, in raise [0x7f98f8c42475]
[move_group-4] #0  | Source "./nptl/pthread_kill.c", line 89, in __pthread_kill_internal
[move_group-4]     | Source "./nptl/pthread_kill.c", line 78, in __pthread_kill_implementation
[move_group-4]       Source "./nptl/pthread_kill.c", line 44, in __pthread_kill [0x7f98f8c969fc]
[move_group-4] Aborted (Signal sent by tkill() 494385 1000)

Expected behavior

Should work with all RMW implementations.

Actual behavior

Segfaults with Fast DDS, which is the default RMW.

@sea-bass
Copy link
Author

sea-bass commented Nov 9, 2023

By the way, the message definition in question is here: https://github.com/ros-planning/moveit_msgs/blob/ros2/msg/DisplayTrajectory.msg

I tried making a simple publisher using this message definition, following the rclcpp tutorials, and the issue was not present there. So there must be something specific about the node being passed into this publisher...

@fujitatomoya
Copy link
Collaborator

either @Barry-Xu-2018 or @iuhilnehc-ynos do you have bandwidth to check this?

@iuhilnehc-ynos
Copy link
Collaborator

From the exception message,
what(): could not create publisher: create_publisher() called for existing topic name rt/display_planned_path with incompatible type moveit_msgs::msg::dds_::DisplayTrajectory_, at ./src/publisher.cpp:145, at ./src/rcl/publisher.c:117,
we can found that it was originally generated at https://github.com/ros2/rmw_fastrtps/blob/a67d6df1d951c980572237e9d4a2683fd2b02546/rmw_fastrtps_cpp/src/publisher.cpp#L138-L147.

bool
find_and_check_topic_and_type(
  const CustomParticipantInfo * participant_info,
  const std::string & topic_name,
  const std::string & type_name,
  eprosima::fastdds::dds::TopicDescription ** returned_topic,
  eprosima::fastdds::dds::TypeSupport * returned_type)
{
  // Searchs for an already existing topic
  *returned_topic = participant_info->participant_->lookup_topicdescription(topic_name);
  if (nullptr != *returned_topic) {
    if ((*returned_topic)->get_type_name() != type_name) {
      return false;
    }
  }

I guess you created another publisher with the same name but different types somewhere.
Could you search the DISPLAY_PATH_TOPIC in your project? If there are fully reproduced steps, I'll appreciate it.

@iuhilnehc-ynos
Copy link
Collaborator

iuhilnehc-ynos commented Nov 14, 2023

I quickly tested demo_nodes_py on rmw_cyclonedds_cpp, which already support one topic name with multiple type names.

Not sure if FastDDS can support this feature. @MiguelCompany

NOTE: I metioned it in ros2/ros2#1095 (comment)

@sea-bass I suggest that you can use different topic names to solve this issue while using different type names.

@sea-bass
Copy link
Author

Thanks @iuhilnehc-ynos -- I will go through and see if there actually were multiple types assigned to the same topic, as that would be a bug on our side to fix.

@sea-bass
Copy link
Author

@Abishalini found the bug. We indeed had an accidental copy-paste error where we had two message types on the same topic. Thanks!

https://github.com/ros-planning/moveit2/blob/beec33dd05adfd0bfd8a58ebec49a90eea89f0ef/moveit_ros/planning/planning_response_adapter_plugins/res/default_response_adapter_params.yaml#L19-L28

@ros-discourse
Copy link

This issue has been mentioned on ROS Discourse. There might be relevant details there:

https://discourse.ros.org/t/manipulation-wg-moveit-maintainer-meeting-november-30-rescheduled/34686/2

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

4 participants