ros2 / rclcpp

rclcpp (ROS Client Library for C++)
Apache License 2.0
534 stars 413 forks source link

find_package rclcpp adds non-existent include dir #1688

Closed rlkandela closed 2 years ago

rlkandela commented 3 years ago

Bug report

Required Info:

Steps to reproduce issue

#include <rclcpp/rclcpp.hpp>

class MyNode: public rclcpp::Node {
  public: 
    typedef std::shared_ptr<MyNode> SharedPtr;
    MyNode():Node("hi"){RCLCPP_INFO(this->get_logger(),"Hello!!");}
};

int main(int argc, char **argv){
  rclcpp::init(argc, argv);

  MyNode::SharedPtr node = std::make_shared<MyNode>();

  rclcpp::spin(node);

  rclcpp::shutdown();

  return 0;
}
cmake_minimum_required(VERSION 3.8)
project(pruebacpp)

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
  add_compile_options(-Wall -Wextra -Wpedantic)
endif()

# find dependencies
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)

if(BUILD_TESTING)
  find_package(ament_lint_auto REQUIRED)
  # the following line skips the linter which checks for copyrights
  # uncomment the line when a copyright and license is not present in all source files
  #set(ament_cmake_copyright_FOUND TRUE)
  # the following line skips cpplint (only works in a git repo)
  # uncomment the line when this package is not in a git repo
  #set(ament_cmake_cpplint_FOUND TRUE)
  ament_lint_auto_find_test_dependencies()
endif()

add_executable(pruebanodo ${CMAKE_SOURCE_DIR}/src/nodo.cpp)
ament_target_dependencies(pruebanodo rclcpp)

install(TARGETS pruebanodo DESTINATION lib/${PROJECT_NAME})

ament_package()

Expected behavior

Build when running colcon build on a workspace which only has that package

Actual behavior

Throws the same error a bunch of times

CMake Error in CMakeLists.txt:
  Imported target "rclcpp::rclcpp" includes non-existent path

    "C:/ci/ws/install/include"

  in its INTERFACE_INCLUDE_DIRECTORIES.  Possible reasons include:

  * The path was deleted, renamed, or moved to another location.

  * An install or uninstall procedure did not complete successfully.

  * The installation package was faulty and references files it does not
  provide.
rlkandela commented 3 years ago

I "solved" it (if this may be considered a solution), by editing share\rcl\cmake\rclExport.cmake, share\rclcpp\cmake\rclcppExport.cmake and share\rcl_lifecycle\cmake\rcl_lifecycleExport.cmake and removing the non-existent path from the INTERFACE_INCLUDE_DIRECTORIES.

YangGou commented 3 years ago

Hello, I encountered the same problem, can you explain it in detail, thank you。

rlkandela commented 3 years ago

@YangGou Of course, but even though it works this might be more of a workaround than an solution. I will explain 2 possible options.

The easy one

Just create the missing route, my error was with C:/ci/ws/install/include, if you create that folder it works.

The tedious one

I have ROS 2 Galactic Geochelone installed at C:\dev\ros2_galactic. What I did was edit the files

Changing the line where appeared the route C:/ci/ws/install/include just by removing that route. For example in rclcppExport.cmake passing from:

INTERFACE_INCLUDE_DIRECTORIES "${_IMPORT_PREFIX}/include;C:/ci/ws/install/include"

to:

# INTERFACE_INCLUDE_DIRECTORIES "${_IMPORT_PREFIX}/include;C:/ci/ws/install/include"
INTERFACE_INCLUDE_DIRECTORIES "${_IMPORT_PREFIX}/include"

I just commented it with a # in case I want to recover the original one.

In case your error is different from mine

All this came from searching recursively at C:\dev\ros2_galactic with grep for "C:/ci/ws/install/include". This leaded me to those tree files. But I guess there might be more files with non-existent paths, if yours is different all you have to do is search the route of your error at your installation folder recursively and "patch" the files that are causing the error by removing that route.

YangGou commented 3 years ago

You are awesome, solved my problem according to your method, thank you very much!

flynneva commented 3 years ago

@ivanpauno any updates on if this will be fixed on the next galactic patch release? is this already fixed in rolling then?

clalancette commented 3 years ago

It's not fixed in Rolling as far as I know. It needs someone to dig into it and figure out what is going on.

flynneva commented 3 years ago

@clalancette i think @rlkandela did most of the leg work already...someone's just gotta implement it.

I think just modifying the changes below to only include that folder during the CI runs would do the trick rather than just commenting it out.

From a @rlkandela above:

"I have ROS 2 Galactic Geochelone installed at C:\dev\ros2_galactic. What I did was edit the files C:\dev\ros2_galactic\share\rcl\cmake\rclExport.cmake C:\dev\ros2_galactic\share\rclcpp\cmake\rclcppExport.cmake C:\dev\ros2_galactic\share\rcl_lifecycle\cmake\rcl_lifecycleExport.cmake Changing the line where appeared the route C:/ci/ws/install/include just by removing that route. For example in rclcppExport.cmake passing from: INTERFACE_INCLUDE_DIRECTORIES "${_IMPORT_PREFIX}/include;C:/ci/ws/install/include" to:

# INTERFACE_INCLUDE_DIRECTORIES "${_IMPORT_PREFIX}/include;C:/ci/ws/install/include" INTERFACE_INCLUDE_DIRECTORIES "${_IMPORT_PREFIX}/include" I just commented it with a # in case I want to recover the original one.

ivanpauno commented 3 years ago

@flynneva those files are automatically generated, so we have to find why there are some absolute paths there, we cannot simply edit the files.

FYI, I think https://gitlab.com/ros-tracing/ros2_tracing/-/merge_requests/252 will solve the issue.

ivanpauno commented 3 years ago

https://gitlab.com/ros-tracing/ros2_tracing/-/merge_requests/252 partially solves the problem, but that's not all unfortunately.

I have downloaded the last binary archive, after going to the share directory and running grep -rn C: I found the following absolute paths (on Windows, use findstr /spin /c:"C:" .\*):

rviz_default_plugins/cmake/rviz_default_pluginsExport.cmake:58:  INTERFACE_INCLUDE_DIRECTORIES "${_IMPORT_PREFIX}/include;C:/Qt/Qt5.12.10/5.12.10/msvc2017_64/include/;C:/Qt/Qt5.12.10/5.12.10/msvc2017_64/i
nclude/QtWidgets;C:/Qt/Qt5.12.10/5.12.10/msvc2017_64/include/QtGui;C:/Qt/Qt5.12.10/5.12.10/msvc2017_64/include/QtCore;C:/Qt/Qt5.12.10/5.12.10/msvc2017_64/.//mkspecs/win32-msvc;C:/Qt/Qt5.12.10/5.12.10/msvc
2017_64/include//QtANGLE;C:/ci/ws/install/include;${_IMPORT_PREFIX}/include"

rviz_default_plugins/cmake/rviz_default_pluginsExport.cmake:59:  INTERFACE_LINK_LIBRARIES "rviz_ogre_vendor::OgreMain;rviz_ogre_vendor::OgreOverlay;geometry_msgs::geometry_msgs__rosidl_generator_c;geometr
y_msgs::geometry_msgs__rosidl_typesupport_fastrtps_c;geometry_msgs::geometry_msgs__rosidl_typesupport_fastrtps_cpp;geometry_msgs::geometry_msgs__rosidl_typesupport_introspection_c;geometry_msgs::geometry_
msgs__rosidl_typesupport_c;geometry_msgs::geometry_msgs__rosidl_generator_cpp;geometry_msgs::geometry_msgs__rosidl_typesupport_introspection_cpp;geometry_msgs::geometry_msgs__rosidl_typesupport_cpp;intera
ctive_markers::interactive_markers;laser_geometry::laser_geometry;nav_msgs::nav_msgs__rosidl_generator_c;nav_msgs::nav_msgs__rosidl_typesupport_fastrtps_c;nav_msgs::nav_msgs__rosidl_typesupport_fastrtps_c
pp;nav_msgs::nav_msgs__rosidl_typesupport_introspection_c;nav_msgs::nav_msgs__rosidl_typesupport_c;nav_msgs::nav_msgs__rosidl_generator_cpp;nav_msgs::nav_msgs__rosidl_typesupport_introspection_cpp;nav_msg
s::nav_msgs__rosidl_typesupport_cpp;map_msgs::map_msgs__rosidl_generator_c;map_msgs::map_msgs__rosidl_typesupport_fastrtps_c;map_msgs::map_msgs__rosidl_typesupport_fastrtps_cpp;map_msgs::map_msgs__rosidl_
typesupport_introspection_c;map_msgs::map_msgs__rosidl_typesupport_c;map_msgs::map_msgs__rosidl_generator_cpp;map_msgs::map_msgs__rosidl_typesupport_introspection_cpp;map_msgs::map_msgs__rosidl_typesuppor
t_cpp;rclcpp::rclcpp;resource_retriever::resource_retriever;rviz_common::rviz_common;rviz_rendering::rviz_rendering;tf2::tf2;tf2_geometry_msgs::tf2_geometry_msgs;tf2_ros::tf2_ros;tf2_ros::static_transform
_broadcaster_node;urdf::urdf;visualization_msgs::visualization_msgs__rosidl_generator_c;visualization_msgs::visualization_msgs__rosidl_typesupport_fastrtps_c;visualization_msgs::visualization_msgs__rosidl
_typesupport_fastrtps_cpp;visualization_msgs::visualization_msgs__rosidl_typesupport_introspection_c;visualization_msgs::visualization_msgs__rosidl_typesupport_c;visualization_msgs::visualization_msgs__ro
sidl_generator_cpp;visualization_msgs::visualization_msgs__rosidl_typesupport_introspection_cpp;visualization_msgs::visualization_msgs__rosidl_typesupport_cpp;C:/ci/ws/install/Lib/image_transport.lib;\$<\
$<NOT:\$<CONFIG:DEBUG>>:C:/ci/ws/install/lib/message_filters.lib>;rclcpp::rclcpp;\$<\$<NOT:\$<CONFIG:DEBUG>>:C:/ci/ws/install/lib/rclcpp.lib>;libstatistics_collector::libstatistics_collector;rcl::rcl;rcl_
yaml_param_parser::rcl_yaml_param_parser;rosgraph_msgs::rosgraph_msgs__rosidl_generator_c;rosgraph_msgs::rosgraph_msgs__rosidl_typesupport_fastrtps_c;rosgraph_msgs::rosgraph_msgs__rosidl_typesupport_fastr
tps_cpp;rosgraph_msgs::rosgraph_msgs__rosidl_typesupport_introspection_c;rosgraph_msgs::rosgraph_msgs__rosidl_typesupport_c;rosgraph_msgs::rosgraph_msgs__rosidl_generator_cpp;rosgraph_msgs::rosgraph_msgs_
_rosidl_typesupport_introspection_cpp;rosgraph_msgs::rosgraph_msgs__rosidl_typesupport_cpp;statistics_msgs::statistics_msgs__rosidl_generator_c;statistics_msgs::statistics_msgs__rosidl_typesupport_fastrtp
s_c;statistics_msgs::statistics_msgs__rosidl_typesupport_fastrtps_cpp;statistics_msgs::statistics_msgs__rosidl_typesupport_introspection_c;statistics_msgs::statistics_msgs__rosidl_typesupport_c;statistics
_msgs::statistics_msgs__rosidl_generator_cpp;statistics_msgs::statistics_msgs__rosidl_typesupport_introspection_cpp;statistics_msgs::statistics_msgs__rosidl_typesupport_cpp;\$<\$<NOT:\$<CONFIG:DEBUG>>:C:/
ci/ws/install/lib/sensor_msgs__rosidl_generator_c.lib>;\$<\$<NOT:\$<CONFIG:DEBUG>>:C:/ci/ws/install/lib/sensor_msgs__rosidl_typesupport_fastrtps_c.lib>;rosidl_typesupport_fastrtps_c::rosidl_typesupport_fa
strtps_c;sensor_msgs::sensor_msgs__rosidl_typesupport_fastrtps_cpp;\$<\$<NOT:\$<CONFIG:DEBUG>>:C:/ci/ws/install/lib/sensor_msgs__rosidl_typesupport_fastrtps_cpp.lib>;rmw::rmw;rosidl_typesupport_fastrtps_c
pp::rosidl_typesupport_fastrtps_cpp;fastcdr;\$<\$<NOT:\$<CONFIG:DEBUG>>:C:/ci/ws/install/lib/sensor_msgs__rosidl_typesupport_introspection_c.lib>;rosidl_typesupport_introspection_c::rosidl_typesupport_int
rospection_c;\$<\$<NOT:\$<CONFIG:DEBUG>>:C:/ci/ws/install/lib/sensor_msgs__rosidl_typesupport_c.lib>;rosidl_typesupport_c::rosidl_typesupport_c;sensor_msgs::sensor_msgs__rosidl_generator_c;\$<\$<NOT:\$<CO
NFIG:DEBUG>>:C:/ci/ws/install/lib/sensor_msgs__rosidl_typesupport_introspection_cpp.lib>;sensor_msgs::sensor_msgs__rosidl_generator_cpp;rosidl_typesupport_introspection_cpp::rosidl_typesupport_introspecti
on_cpp;\$<\$<NOT:\$<CONFIG:DEBUG>>:C:/ci/ws/install/lib/sensor_msgs__rosidl_typesupport_cpp.lib>;rosidl_runtime_c::rosidl_runtime_c;rosidl_runtime_cpp::rosidl_runtime_cpp;rosidl_typesupport_cpp::rosidl_ty
pesupport_cpp;rosidl_typesupport_interface::rosidl_typesupport_interface;builtin_interfaces::builtin_interfaces__rosidl_generator_c;builtin_interfaces::builtin_interfaces__rosidl_typesupport_fastrtps_c;bu
iltin_interfaces::builtin_interfaces__rosidl_typesupport_fastrtps_cpp;builtin_interfaces::builtin_interfaces__rosidl_typesupport_introspection_c;builtin_interfaces::builtin_interfaces__rosidl_typesupport_
c;builtin_interfaces::builtin_interfaces__rosidl_generator_cpp;builtin_interfaces::builtin_interfaces__rosidl_typesupport_introspection_cpp;builtin_interfaces::builtin_interfaces__rosidl_typesupport_cpp;g
eometry_msgs::geometry_msgs__rosidl_generator_c;geometry_msgs::geometry_msgs__rosidl_typesupport_fastrtps_c;geometry_msgs::geometry_msgs__rosidl_typesupport_fastrtps_cpp;geometry_msgs::geometry_msgs__rosi
dl_typesupport_introspection_c;geometry_msgs::geometry_msgs__rosidl_typesupport_c;geometry_msgs::geometry_msgs__rosidl_generator_cpp;geometry_msgs::geometry_msgs__rosidl_typesupport_introspection_cpp;geom
etry_msgs::geometry_msgs__rosidl_typesupport_cpp;std_msgs::std_msgs__rosidl_generator_c;std_msgs::std_msgs__rosidl_typesupport_fastrtps_c;std_msgs::std_msgs__rosidl_typesupport_fastrtps_cpp;std_msgs::std_
msgs__rosidl_typesupport_introspection_c;std_msgs::std_msgs__rosidl_typesupport_c;std_msgs::std_msgs__rosidl_generator_cpp;std_msgs::std_msgs__rosidl_typesupport_introspection_cpp;std_msgs::std_msgs__rosi
dl_typesupport_cpp;ament_index_cpp::ament_index_cpp;class_loader::class_loader;rcutils::rcutils;rcpputils::rcpputils;tinyxml2::tinyxml2"

Output ``` rviz_rendering/cmake/rviz_renderingExport.cmake:57: INTERFACE_INCLUDE_DIRECTORIES "${_IMPORT_PREFIX}/include;C:/ProgramData/chocolatey/lib/eigen/include;C:/ci/ws/install/opt/rviz_assimp_vendor/include;$$ _IMPORT_PREFIX}/include" rviz_rendering/cmake/rviz_renderingExport.cmake:58: INTERFACE_LINK_LIBRARIES "rviz_ogre_vendor::OgreMain;rviz_ogre_vendor::OgreOverlay;Qt5::Widgets;ament_index_cpp::ament_index_cpp;resource_retriever::r$ source_retriever;C:/ci/ws/install/opt/rviz_assimp_vendor/lib/assimp-vc140-mt.lib" ```
ivanpauno commented 3 years ago

If someone wants to help, fixing the absolute paths for Qt, assimp, eigen, log4cxx shouldn't be too hard. It requires updating our CMakelists.txt files so we use the exported targets instead of the old libraries/include variables (e.g. this will work for Qt). If they are not exporting targets, write a helper Find*.cmake, see this.

audrow commented 2 years ago

Bump @ivanpauno

ivanpauno commented 2 years ago

@audrow @clalancette FYI there are still a lot of issues related to this. I'm cleaning up a list of issues, and I will try to solve some of them.