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

Moveit linking problem

asked 2021-08-26 10:35:52 -0500

appie gravatar image

updated 2021-08-26 11:06:11 -0500

gvdhoorn gravatar image

Hello,

My package was woriking fine with the previous version of ros-melodic-moveit which install lib-moveit-*1.0.7 but after updating to the new one which install lib-moveit-***1.0.8 I had the following error message when use catkin_make:

/opt/ros/melodic/lib/libmoveit_ros_occupancy_map_monitor.so : undefined reference to octomath::Pose6D(octomath::Pose6D const&).

How can I solve this issue, Otherwise how can I install the previous version of moveit?

Regards,

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2021-08-26 10:50:52 -0500

Ranjit Kathiriya gravatar image

updated 2021-08-26 11:03:46 -0500

Hello @appie,

Can you please! look at the following things I think you might solve the problem and You did not need to install the previous version. I think you forgot to define OCTOMAP libraries and directories into your catkin.txt file.

In CMakeLists.txt

include_directories(${OCTOMAP_INCLUDE_DIRS}) 
target_link_libraries(${OCTOMAP_LIBRARIES})

and This also

find_package(Boost REQUIRED thread)
[...]
find_package(Eigen3 REQUIRED)  # Check this line
find_package(octomap REQUIRED)  # Check this line
catkin_package(
  INCLUDE_DIRS
    include
  LIBRARIES
      ${MOVEIT_LIB_NAME}  
  CATKIN_DEPENDS
     moveit_core
     moveit_msgs
     geometric_shapes
     tf2_ros
   DEPENDS
     EIGEN3
     OCTOMAP  # Check this line
)

include_directories(include)
include_directories(SYSTEM
        ${catkin_INCLUDE_DIRS}
        ${Boost_INCLUDE_DIRS}
        ${EIGEN3_INCLUDE_DIRS}
        ${X11_INCLUDE_DIR}
        )

add_library(${MOVEIT_LIB_NAME}
          src/occupancy_map_monitor.cpp
          src/occupancy_map_updater.cpp
          )

set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}")
target_link_libraries(${MOVEIT_LIB_NAME} ${catkin_LIBRARIES} ${Boost_LIBRARIES})
add_executable(moveit_ros_occupancy_map_server src/occupancy_map_server.cpp)
target_link_libraries(moveit_ros_occupancy_map_server ${MOVEIT_LIB_NAME} ${catkin_LIBRARIES} ${Boost_LIBRARIES})

For Ref: look at this link https://github.com/ros-planning/movei...

Feel free to drop a comment if you have any issues.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2021-08-26 10:35:52 -0500

Seen: 335 times

Last updated: Aug 26 '21