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

colcon build moveit2 failure because of moveit_ros_warehouse collect2 error

asked 2021-07-03 18:21:42 -0500

Daggrosh gravatar image

updated 2021-07-04 20:44:03 -0500

I'm building moveit2 from this tutorial: moveit2_tutorials.picknik.ai/doc/getting_started/getting_started.html

I'm on Ubuntu 20.04 and my ros2 version is foxy, which was built from debian. Rosdep returns all rosdeps installed successfully and moveit2's repos have been successfully cloned.

I'm getting this when building:

--- stderr: moveit_ros_warehouse /usr/bin/ld: libmoveit_warehouse.so.: undefined reference to `MD5' collect2: error: ld returned 1 exit status

Here is the code from colcon build:

:~/robotics/moveo_ws/ws$ colcon build --event-handlers desktop_notification- status- >--cmake-args -DCMAKE_BUILD_TYPE=Release

Starting >>> geometric_shapes [Processing: geometric_shapes] [Processing: geometric_shapes] [Processing: geometric_shapes] [Processing: geometric_shapes] Finished <<< geometric_shapes [2min 1s] Starting >>> moveit_msgs Finished <<< moveit_msgs [7.18s] Starting >>> srdfdom Finished <<< srdfdom [0.52s] Starting >>> moveit_common Finished <<< moveit_common [0.27s] Starting >>> controller_manager_msgs Finished <<< controller_manager_msgs [2.03s] Starting >>> ros2_control_test_assets Finished <<< ros2_control_test_assets [0.25s] Starting >>> hardware_interface Finished <<< hardware_interface [0.98s] Starting >>> controller_interface Finished <<< controller_interface [0.66s] Starting >>> controller_manager Finished <<< controller_manager [1.18s] Starting >>> warehouse_ros Finished <<< warehouse_ros [0.45s] Starting >>> moveit_resources_panda_description Finished <<< moveit_resources_panda_description [0.26s] Starting >>> moveit_resources_panda_moveit_config Finished <<< moveit_resources_panda_moveit_config [0.28s] Starting >>> moveit_resources_fanuc_description Finished <<< moveit_resources_fanuc_description [0.26s] Starting >>> moveit_resources_fanuc_moveit_config Finished <<< moveit_resources_fanuc_moveit_config [0.27s] Starting >>> forward_command_controller Finished <<< forward_command_controller [0.63s] Starting >>> moveit_resources_pr2_description Finished <<< moveit_resources_pr2_description [0.30s] Starting >>> moveit_core Finished <<< moveit_core [4.59s] Starting >>> moveit_ros_occupancy_map_monitor Finished <<< moveit_ros_occupancy_map_monitor [0.48s] Starting >>> moveit_ros_planning Finished <<< moveit_ros_planning [2.06s] Starting >>> moveit_kinematics Finished <<< moveit_kinematics [0.98s] Starting >>> moveit_ros_warehouse --- stderr: moveit_ros_warehouse /usr/bin/ld: libmoveit_warehouse.so.: undefined reference to `MD5' collect2: error: ld returned 1 exit status make[2]: * [warehouse/CMakeFiles/moveit_warehouse_broadcast.dir/build.make:346: warehouse/moveit_warehouse_broadcast] Error 1 make[1]: [CMakeFiles/Makefile2:189: warehouse/CMakeFiles/moveit_warehouse_broadcast.dir/all] Error 2 make: ** [Makefile:141: all] Error 2

Failed <<< moveit_ros_warehouse [1.37s, exited with code 2]

Summary: 20 packages finished [2min 27s] 1 package failed: moveit_ros_warehouse 1 package had stderr output: moveit_ros_warehouse 33 packages not processed

I see this and look closer at ws/build/moveit_ros_warehouse/CMakeFiles and cat CMakeError.log. Here is the cat:

Performing C SOURCE FILE Test CMAKE_HAVE_LIBC_PTHREAD failed with the >following output: Change Dir: /home/forrest/robotics/moveo_ws/ws/build/moveit_ros_warehouse/CMakeFiles/CMakeTmp

Run Build Command(s):/usr/bin/make cmTC_6c77e/fast && /usr/bin/make -f CMakeFiles/cmTC_6c77e.dir /build.make CMakeFiles/cmTC_6c77e.dir/build make[1]: Entering directory '/home/forrest/robotics/moveo_ws/ws/build/moveit_ros_warehouse/CMakeFile/CMakeTmp' Building C object CMakeFiles/cmTC_6c77e.dir/src.c.o /usr/bin/cc -DCMAKE_HAVE_LIBC_PTHREAD -o CMakeFiles/cmTC_6c77e.dir/src.c.o -c /home/forrest/robotics/moveo_ws/ws/build/moveit_ros_warehouse/CMakeFiles/CMakeTmp/src.c Linking C executable cmTC_6c77e /usr/bin/cmake -E cmake_link_script CMakeFiles/cmTC_6c77e.dir/link.txt --verbose=1 /usr/bin/cc -DCMAKE_HAVE_LIBC_PTHREAD CMakeFiles/cmTC_6c77e.dir/src.c.o -o cmTC_6c77e /usr/bin/ld: CMakeFiles/cmTC_6c77e.dir/src.c.o: in function main': src.c:(.text+0x46): undefined reference topthread_create' /usr/bin/ld: src.c:(.text ...

(more)
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2021-07-05 07:06:50 -0500

jafar_abdi gravatar image

I just tried building it from source and I didn't have any error, can you share more info, which commits hash are you using for each package .? what's the output of echo $AMENT_PREFIX_PATH .? what's the output for the following command apt policy ros-foxy-warehouse-ros ros-foxy-warehouse-ros-mongo .?

edit flag offensive delete link more

Comments

The ament prefix path output is: /opt/ros/foxy

The output for the apt policy is: ros-foxy-warehouse-ros: Installed: 2.0.1-1focal.20210601.182449 Candidate: 2.0.1-1focal.20210601.182449 Version table: * 2.0.1-1focal.20210601.182449 500 500 http://packages.ros.org/ros2/ubuntu focal/main amd64 Packages 100 /var/lib/dpkg/status ros-foxy-warehouse-ros-mongo: Installed: 2.0.2-1focal.20210618.005428 Candidate: 2.0.2-1focal.20210618.005428 Version table: *2.0.2-1focal.20210618.005428 500 500 http://packages.ros.org/ros2/ubuntu focal/main amd64 Packages 100 /var/lib/dpkg/status

More information: I have built moveit2 up until the packages depending on moveit_ros_warehouse (which total 11 packages) using the --continue-on-error colcon command, so I have successfully installed warehouse_ros and warehouse_ros_mongo.

Daggrosh gravatar image Daggrosh  ( 2021-07-05 21:08:17 -0500 )edit

I have since tried to build moveit2 again in a fresh ws. Here are the exact steps, which ended with the same error:

mkdir moveit2_test cd moveit2_test git clone git@github.com:ros-planning/moveit2 #successful mv moveit2 src rosdep install -i -r --from-paths src --ignore src --rosdistro foxy -y #successful colcon build --event-handlers desktop_notification- status- --cmake-args -DCMAKE_BUILD_TYPE=Release #successful until moveit_ros_warehouse

error: --- stderr: moveit_ros_warehouse /usr/bin/ld: libmoveit_warehouse.so.: undefined reference to `MD5' collect2: error: ld returned 1 exit status make[2]: * [warehouse/CMakeFiles/moveit_warehouse_broadcast.dir/build.make:346: warehouse/moveit_warehouse_broadcast] Error 1 make[1]: [CMakeFiles/Makefile2:189: warehouse/CMakeFiles/moveit_warehouse_broadcast.dir/all] Error 2 make: ** [Makefile:141: all] Error 2

I also got a stderror output for moveit_core, but it was a warning and don't think it's a big deal

Daggrosh gravatar image Daggrosh  ( 2021-07-05 22:39:18 -0500 )edit
1

After debugging it further, I think this's due to a bug in ament_cmake where it does prefer the system installed package rather than the source one, if you remove these packages ros-foxy-warehouse-rosros-foxy-warehouse-ros-mongo it should pass

jafar_abdi gravatar image jafar_abdi  ( 2021-07-06 06:16:15 -0500 )edit

It worked! You're magic man, thanks so much

Daggrosh gravatar image Daggrosh  ( 2021-07-07 02:27:31 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2021-07-03 18:21:42 -0500

Seen: 1,312 times

Last updated: Jul 05 '21