-
Notifications
You must be signed in to change notification settings - Fork 554
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
'joint_state_broadcaster' [move_group-4] terminate called after throwing an instance of 'rclcpp::ParameterTypeException' #2854
Comments
Sorry, I missed an error log: there is an error before " terminate called...." line[move_group-4] [INFO] [1716737911.250374500] [move_group.moveit.moveit.ros.planning_scene_monitor]: Listening to 'planning_scene_world' for planning scene world geometry |
[rviz2-1] [INFO] [1716737911.505383600] [rviz2]: Stereo is NOT SUPPORTED |
The 3D sensor error is unrelated and can be ignored. it just happens to be directly before the real problems start and is therefore quite missleading. Fix for ROS Jazzy: in the replace - planning_plugin: ompl_interface/OMPLPlanner
- request_adapters: >-
- default_planner_request_adapters/AddTimeOptimalParameterization
- default_planner_request_adapters/ResolveConstraintFrames
- default_planner_request_adapters/FixWorkspaceBounds
- default_planner_request_adapters/FixStartStateBounds
- default_planner_request_adapters/FixStartStateCollision
- default_planner_request_adapters/FixStartStatePathConstraints
+ planning_plugins:
+ - ompl_interface/OMPLPlanner
+ # The order of the elements in the adapter corresponds to the order they are processed by the motion planning pipeline.
+ request_adapters:
+ - default_planning_request_adapters/ResolveConstraintFrames
+ - default_planning_request_adapters/ValidateWorkspaceBounds
+ - default_planning_request_adapters/CheckStartStateBounds
+ - default_planning_request_adapters/CheckStartStateCollision
+ response_adapters:
+ - default_planning_response_adapters/AddTimeOptimalParameterization
+ - default_planning_response_adapters/ValidateSolution
+ - default_planning_response_adapters/DisplayMotionPath This actually needs a fix in ros2_kortex AND moveit2_tutorials which pulls in this repository Came across infos in the moveit migration notes |
Many thanks, it looks works, no warning in panel now. |
See also #2887 |
Hello,
I follow "MoveIt Quickstart in RViz" tutorial to run ros2 launch moveit2_tutorials demo.launch.py after build moveit.
But "displays panel" shows warning "Requesting initial scene failed" both under PlanningScene and MotionPlanning dir.
Steps to reproduce
follow "MoveIt Quickstart in RViz"
until ros2 launch moveit2_tutorials demo.launch.py
Expected behaviour
display is not same as tutorial.
Actual behaviour
warnning displayed
Backtrace or Console output
[ros2_control_node-5] [INFO] [1716735893.396328900] [controller_manager]: Loading controller 'joint_state_broadcaster'
[move_group-4] terminate called after throwing an instance of 'rclcpp::ParameterTypeException'
[move_group-4] what(): expected [string_array] got [string]
[move_group-4] Stack trace (most recent call last):
[move_group-4] #17 Object "", at 0xffffffffffffffff, in
[move_group-4] #16 Object "/home/sfl/workspace/install/moveit_ros_move_group/lib/moveit_ros_move_group/move_group", at 0x7fcceb185094, in _start
[move_group-4] #15 Object "/usr/lib/x86_64-linux-gnu/libc.so.6", at 0x7fccea699e3f, in __libc_start_main
[move_group-4] #14 Object "/usr/lib/x86_64-linux-gnu/libc.so.6", at 0x7fccea699d8f, in
[move_group-4] #13 Object "/home/sfl/workspace/install/moveit_ros_move_group/lib/moveit_ros_move_group/move_group", at 0x7fcceb18421e, in main
[move_group-4] #12 Object "/home/sfl/workspace/install/moveit_ros_planning/lib/libmoveit_cpp.so.2.9.0", at 0x7fcceb00f287, in moveit_cpp::MoveItCpp::MoveItCpp(std::shared_ptrrclcpp::Node const&, moveit_cpp::MoveItCpp::Options const&)
[move_group-4] #11 Object "/home/sfl/workspace/install/moveit_ros_planning/lib/libmoveit_cpp.so.2.9.0", at 0x7fcceb00e28b, in moveit_cpp::MoveItCpp::loadPlanningPipelines(moveit_cpp::MoveItCpp::PlanningPipelineOptions const&)
[move_group-4] #10 Object "/home/sfl/workspace/install/moveit_ros_planning/lib/libmoveit_planning_pipeline_interfaces.so.2.9.0", at 0x7fccea3e6c76, in moveit::planning_pipeline_interfaces::createPlanningPipelineMap(std::vector<std::__cxx11::basic_string<char, std::char_traits, std::allocator >, std::allocator<std::__cxx11::basic_string<char, std::char_traits, std::allocator > > > const&, std::shared_ptr<moveit::core::RobotModel const> const&, std::shared_ptrrclcpp::Node const&, std::__cxx11::basic_string<char, std::char_traits, std::allocator > const&)
[move_group-4] #9 Object "/home/sfl/workspace/install/moveit_ros_planning/lib/libmoveit_planning_pipeline.so.2.9.0", at 0x7fccea261d96, in planning_pipeline::PlanningPipeline::PlanningPipeline(std::shared_ptr<moveit::core::RobotModel const> const&, std::shared_ptrrclcpp::Node const&, std::__cxx11::basic_string<char, std::char_traits, std::allocator > const&)
[move_group-4] #8 Object "/home/sfl/workspace/install/moveit_ros_planning/lib/libmoveit_planning_pipeline.so.2.9.0", at 0x7fccea2a5ff3, in planning_pipeline_parameters::ParamListener::declare_params()
[move_group-4] #7 Object "/opt/ros/humble/lib/librclcpp.so", at 0x7fcceac01863, in
[move_group-4] #6 Object "/usr/lib/x86_64-linux-gnu/libstdc++.so.6.0.30", at 0x7fccea96e4d7, in __cxa_throw
[move_group-4] #5 Object "/usr/lib/x86_64-linux-gnu/libstdc++.so.6.0.30", at 0x7fccea96e276, in std::terminate()
[move_group-4] #4 Object "/usr/lib/x86_64-linux-gnu/libstdc++.so.6.0.30", at 0x7fccea96e20b, in
[move_group-4] #3 Object "/usr/lib/x86_64-linux-gnu/libstdc++.so.6.0.30", at 0x7fccea962b9d, in
[move_group-4] #2 Object "/usr/lib/x86_64-linux-gnu/libc.so.6", at 0x7fccea6987f2, in abort
[move_group-4] #1 Object "/usr/lib/x86_64-linux-gnu/libc.so.6", at 0x7fccea6b2475, in raise
[move_group-4] #0 Object "/usr/lib/x86_64-linux-gnu/libc.so.6", at 0x7fccea7069fc, in pthread_kill
[move_group-4] Aborted (Signal sent by tkill() 9615 1000)
....
[ros2_control_node-5] [INFO] [1716735893.418056000] [joint_state_broadcaster]: 'joints' or 'interfaces' parameter is empty. All available state interfaces will be published
[spawner-6] [INFO] [1716735893.431671600] [spawner_joint_state_broadcaster]: Configured and activated joint_state_broadcaster
[rviz2-1] [WARN] [1716735893.447670900] [rcl.logging_rosout]: Publisher already registered for provided node name. If this is due to multiple nodes with the same name then all logs for that logger name will go out over the existing publisher. As soon as any node with that name is destructed it will unregister the publisher, preventing any further logs for that name from being published on the rosout topic.
[rviz2-1] Warning: class_loader.impl: SEVERE WARNING!!! A namespace collision has occurred with plugin factory for class rviz_default_plugins::displays::InteractiveMarkerDisplay. New factory will OVERWRITE existing one. This situation occurs when libraries containing plugins are directly linked against an executable (the one running right now generating this message). Please separate plugins out into their own library or just don't link against the library and use either class_loader::ClassLoader/MultiLibraryClassLoader to open.
...
[rviz2-1] [INFO] [1716735900.019674700] [rviz2.moveit.ros.robot_interaction]: No active joints or end effectors found for group 'gripper'. Make sure that kinematics.yaml is loaded in this node's namespace.
[rviz2-1] [INFO] [1716735900.020273600] [rviz2.moveit.ros.robot_interaction]: No active joints or end effectors found for group 'gripper'. Make sure that kinematics.yaml is loaded in this node's namespace.
[rviz2-1] [INFO] [1716735904.898212400] [rviz2.moveit.ros.planning_scene_monitor]: Failed to call service get_planning_scene, have you launched move_group or called psm.providePlanningSceneService()?
[rviz2-1] [INFO] [1716735905.076620500] [rviz2.moveit.ros.planning_scene_monitor]: Failed to call service get_planning_scene, have you launched move_group or called psm.providePlanningSceneService()?
Use gist.github.com to copy-paste the console output or segfault backtrace using gdb.
Could you help me to find out what is the problem?
thank you, I am a freshman on this.
The text was updated successfully, but these errors were encountered: