ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

Symbol lookup error when using stomp_moveit.

asked 2018-08-24 09:35:04 -0500

Long Smith gravatar image

updated 2018-08-24 10:30:30 -0500

One more symbol lookup question for ros answers.

I run the example for panda robot and STOMP planner from this page. However instead of planned paths I get the annoying error:

/opt/ros/melodic/lib/moveit_ros_move_group/move_group: symbol lookup error: /home/yuriy/Documents/Projects/ROS/ros_arm_workspace/devel/lib/libstomp_moveit_noisy_filters.so: undefined symbol: _ZN2tf15pointEigenToMsgERKN5Eigen6MatrixIdLi3ELi1ELi0ELi3ELi1EEERN13geometry_msgs6Point_ISaIvEEE

Error occurs whenever I push Plan button in RVIZ.

c++filt for this symbol produce the following output:

tf::pointEigenToMsg(Eigen::Matrix<double, 3, 1, 0, 3, 1> const&, geometry_msgs::Point_<std::allocator<void> >&)

stomp_core and stomp_moveit are built from sources using https://github.com/ros-industrial/ind... repo. It seems strange that error occurs inside stomp_moveit package since tutorial clearly states

You only need to build the stomp_core package from industrial_moveit as other packages are not required for the functionality of STOMP with moveIt.

I use ubuntu 18.04 and melodic distribution.

P.S. I have tried to remove build and devel folders and rebuild the workspace. That does not help.

edit retag flag offensive close merge delete

Comments

Hello,

I have the same problem/error while using STOMP. I also online installed the stomp_core package.

Did you find a solution for this error?

Thanks.

DieterWuytens gravatar image DieterWuytens  ( 2018-11-03 15:51:19 -0500 )edit
1

@DieterWuytens I have commented lines 85 and 250 in stomp_moveit/src/noisy_filters/multi_trajectory_visualization.cpp. It will break visualization if you use it but planner will work.

Long Smith gravatar image Long Smith  ( 2018-11-20 15:56:26 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
0

answered 2019-03-05 23:53:02 -0500

Rhys_McK gravatar image

You need to include eigen_conversions to find_package(catkin REQUIRED COMPONENTS ...) in the CMakeList and in the package.xml of the stomp_moveit package. I have made a PR to fix this.

edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2018-08-24 09:35:04 -0500

Seen: 1,095 times

Last updated: Mar 05 '19