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

How can I build navigation2 from source?

asked 2020-02-12 09:17:27 -0500

lorenzo gravatar image

updated 2020-02-12 09:36:32 -0500

I have installed "ROS 2 Eloquent Elusor - Patch Release 1" from https://github.com/ros2/ros2/releases. It works well, in fact I can run the examples of publisher/listener. I want now to build navigation2 from source, but when I do it:

lorenzoteo@lorenzoteo-HP-ZBook-15v-G5:~/navigation2$ colcon build --symlink-install
Starting >>> nav2_common
Starting >>> nav_2d_msgs
Starting >>> nav2_gazebo_spawner
--- stderr: nav2_common                                                                                              
CMake Error at CMakeLists.txt:5 (find_package):
  By not providing "Findament_cmake_core.cmake" in CMAKE_MODULE_PATH this
  project has asked CMake to find a package configuration file provided by
  "ament_cmake_core", but CMake did not find one.

  Could not find a package configuration file provided by "ament_cmake_core"
  with any of the following names:

    ament_cmake_coreConfig.cmake
    ament_cmake_core-config.cmake

  Add the installation prefix of "ament_cmake_core" to CMAKE_PREFIX_PATH or
  set "ament_cmake_core_DIR" to a directory containing one of the above
  files.  If "ament_cmake_core" provides a separate development package or
  SDK, be sure it has been installed.


---
Failed   <<< nav2_common    [ Exited with code 1 ]
Aborted  <<< nav2_gazebo_spawner                                                                     
--- stderr: nav_2d_msgs                                     
CMake Error at CMakeLists.txt:4 (find_package):
  By not providing "Findgeometry_msgs.cmake" in CMAKE_MODULE_PATH this
  project has asked CMake to find a package configuration file provided by
  "geometry_msgs", but CMake did not find one.

  Could not find a package configuration file provided by "geometry_msgs"
  with any of the following names:

    geometry_msgsConfig.cmake
    geometry_msgs-config.cmake

  Add the installation prefix of "geometry_msgs" to CMAKE_PREFIX_PATH or set
  "geometry_msgs_DIR" to a directory containing one of the above files.  If
  "geometry_msgs" provides a separate development package or SDK, be sure it
  has been installed.


---
Aborted  <<< nav_2d_msgs

Summary: 0 packages finished [1.04s]
  1 package failed: nav2_common
  2 packages aborted: nav2_gazebo_spawner nav_2d_msgs
  2 packages had stderr output: nav2_common nav_2d_msgs
  26 packages not processed

Why?

edit retag flag offensive close merge delete

Comments

Have you followed instructions from here? It looks like it's not find certain ros2 packages. Have you sourced your ros2_ws?

Sidd gravatar image Sidd  ( 2020-02-12 14:13:15 -0500 )edit

2 Answers

Sort by ยป oldest newest most voted
0

answered 2020-02-14 03:59:35 -0500

marguedas gravatar image

updated 2020-05-04 01:14:56 -0500

This is an answer to the follow-up question in the comments. As it doesn't fit in a comment I post it as an answer.

@lorenzo as your original issue (not finding the ROS packages in CMake) has been addressed by the original answer, it would be better in the future to accept the original answer and ask follow-up questions as separate questions so that users facing it can find the answer more easily when searching this site.

The issue you are facing is because some RViz components are not relocatable (the paths are hard-coded to the path it had on the build machine) More details at: - https://github.com/osrf/docker_images... - https://github.com/ament/ament_cmake/... - https://github.com/ros-planning/navig...

The work-arounds can be:

1) create the folder it expects and create a symbolic link to it

mkdir -p /home/jenkins-agent/workspace/ci_packaging_linux/ws/install/
ln -s ~/ros2_eloquent/ros2-linux /home/jenkins-agent/workspace/ci_packaging_linux/ws/install/

2) replace all the hard-coded paths to the one on your machine (search replace /home/jenkins-agent/workspace/ci_packaging_linux/ws/install/ with /home/lorenzoteo/ros2_eloquent/ros2-linux/

3) Ubuntu only: If you are on Ubuntu, I recommend this solution as it's less of a work around. Install ROS 2 from debian packages and not from the release archive, this has multiple advantages including but not limited to:

  • RViz is compiled with the right destination path so this issue does not happen
  • The package manager handles the installation and will handle subsequent updates
  • Can easily install additional ROS packages without mixing install paths
edit flag offensive delete link more
1

answered 2020-02-12 15:36:05 -0500

updated 2020-05-04 01:14:49 -0500

Hi,

We've compiled a bunch of instructions for navigation2 here (https://navigation.ros.org/build_inst...). Have you taken a look and having a problem?

The error you're describing is pretty fundamental - you haven't sourced either your ROS2 install /opt/ros/<version>/setup.bash or ROS2 workspace /path/to/ws/install/setup.bash.

edit flag offensive delete link more

Comments

Hi Steve. The point is that I followed VERY carefully the build instruction and source the workspace, but it doesn't work anyway.

Edit:

My directory tree of ROS2 installation (installation from .tar.bz2) is slightly different from the one in the guide:

~/ros2_eloquent/ros2-linux/setup.bash --> this is my directory tree

~/ros2_ws/install/setup.bash --> this is the directory tree written in the instructions

lorenzo gravatar image lorenzo  ( 2020-02-13 01:55:04 -0500 )edit

EDIT:

Partial results of the terminal after the colcon build:

lorenzoteo@lorenzoteo-HP-ZBook-15v-G5:~/navigation2_ws$ colcon build --symlink-install
Starting >>> nav2_common
Starting >>> nav_2d_msgs
.......
--- stderr: nav2_rviz_plugins                                                                                                                    
make[2]: *** No rule to make target '/home/jenkins-agent/workspace/ci_packaging_linux/ws/install/lib/libclass_loader.so', needed by 'libnav2_rviz_plugins.so'.  Stop.
make[2]: *** Waiting for unfinished jobs....
make[1]: *** [CMakeFiles/nav2_rviz_plugins.dir/all] Error 2
make: *** [all] Error 2
---
Failed   <<< nav2_rviz_plugins  [ Exited with code 2 ]
......

P.S. rviz is installed correctly

lorenzo gravatar image lorenzo  ( 2020-02-13 03:04:39 -0500 )edit

You may not have class loader installed, have you run rosdep?

Also why is this on a jenkins agent? Please try building this locally first before adding that complexity into it.

stevemacenski gravatar image stevemacenski  ( 2020-02-13 17:17:10 -0500 )edit

Of course I run rosdep as it is written in istructions. I do not know why is on a jenkins agent. I am following line after line these instructions: https://navigation.ros.org/build_inst...

lorenzo gravatar image lorenzo  ( 2020-02-14 01:54:04 -0500 )edit

Question Tools

3 followers

Stats

Asked: 2020-02-12 09:17:27 -0500

Seen: 1,301 times

Last updated: May 04 '20