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

ROS library cannot find service built in the same package

asked 2020-06-19 03:54:43 -0500

MCmobil gravatar image

updated 2022-01-22 16:16:18 -0500

Evgeny gravatar image

Hello,

I had experienced a weird issue: I am creating in the same package a service, a library relying on this service, and some executable. Whenever I clean my workspace (remove devel and build) and do a casual catkin_make, it is saying my libraries cannot find my generated service.

BUT if I source setup.bash do again a catkin_make, source one more time and do catkin_make, it can generate nicely without any error.

My question is: Did I mistook by trying to do everything in the same package? Should I divide or I should change my CMakeLists?

Here is my CMakeLists:

cmake_minimum_required(VERSION 2.8.3)
project(ndt)

add_compile_options(-std=c++11)
SET(CMAKE_CXX_FLAGS "-O2 -g -Wall ${CMAKE_CXX_FLAGS}")

find_package(catkin REQUIRED COMPONENTS
  roslaunch
  geometry_msgs
  nav_msgs
  sensor_msgs
  roscpp
  rospy
  std_msgs
  cv_bridge
  image_transport
  tf
  message_generation
)

add_service_files(
  FILES
  GpsData.srv
)

generate_messages(DEPENDENCIES geometry_msgs)

find_package(Eigen3 REQUIRED)
find_package(PCL REQUIRED)
find_package(OpenCV 3 REQUIRED)

if (CATKIN_ENABLE_TESTING)
  find_package(roslaunch REQUIRED)
  roslaunch_add_file_check(launch USE_TEST_DEPENDENCIES)
endif()

include_directories(include
    ${catkin_INCLUDE_DIRS} 
    ${EIGEN3_INCLUDE_DIR}
    ${PCL_INCLUDE_DIRS}
  ${OPENCV_INCLUDE_DIRS}
)

include_directories(/usr/include)

add_library(ndt_func SHARED library/ndt_func.cpp)
add_library(ndt_func_nogps SHARED library/ndt_func_nogps.cpp)

catkin_package(
  INCLUDE_DIRS include
  LIBRARIES ndt_func ndt_func_nogps
  CATKIN_DEPENDS geometry_msgs nav_msgs roscpp rospy std_msgs cv_bridge
  DEPENDS EIGEN3 PCL OpenCVlibraaries
)

add_executable(ndt_loc src/code/ndt_node.cpp)
target_include_directories(ndt_loc PRIVATE ${OpenCV_INCLUDE_DIRS} ${PCL_INCLUDE_DIRS})
target_link_libraries(ndt_loc ndt_func ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${OpenCV_LIBS} /usr/lib/liblas.so)

add_executable(ndt_loc_nogps src/tests/ndt_node_nogps.cpp)
target_include_directories(ndt_loc_nogps PRIVATE ${OpenCV_INCLUDE_DIRS} ${PCL_INCLUDE_DIRS})
target_link_libraries(ndt_loc_nogps ndt_func_nogps ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${OpenCV_LIBS} /usr/lib/liblas.so)

add_executable(ndt_loc_ref src/tests/ndt_node_ref.cpp)
target_include_directories(ndt_loc_ref PRIVATE ${OpenCV_INCLUDE_DIRS} ${PCL_INCLUDE_DIRS})
target_link_libraries(ndt_loc_ref ndt_func_nogps ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${OpenCV_LIBS} /usr/lib/liblas.so)

add_executable(test_gps src/tests/test_gps.cpp)
add_dependencies(test_gps ${ndt_EXPORTED_TARGETS})
target_link_libraries(test_gps ${catkin_LIBRARIES})

#add_executable(ndt_map src/ndt_map_node.cpp)
#target_include_directories(ndt_map PRIVATE ${OpenCV_INCLUDE_DIRS} ${PCL_INCLUDE_DIRS})
#target_link_libraries(ndt_map ndt_func ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${OpenCV_LIBS} /usr/lib/liblas.so)

add_executable(ndt_data_transfer src/code/ndt_data_transfer.cpp)
add_dependencies(ndt_data_transfer ${ndt_EXPORTED_TARGETS})
target_link_libraries(ndt_data_transfer ${catkin_LIBRARIES})

add_executable(ndt_data_transfer_noscore src/tests/ndt_data_transfer_noscore.cpp)
target_link_libraries(ndt_data_transfer_noscore ${catkin_LIBRARIES})

#add_executable(GPS_message src/code/GPS_message.cpp)
#target_link_libraries(GPS_message ${catkin_LIBRARIES})

install(DIRECTORY 
        DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION})

install(TARGETS ndt_func
   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

install(TARGETS ndt_loc ndt_loc_nogps ndt_data_transfer ndt_data_transfer_noscore test_gps #ndt_map ndt_loc_gps ndt_loc_ref 
   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

install(DIRECTORY include/${PROJECT_NAME}/
   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
)

Here the output after cleaning (only for this package):

####
#### Running command: "make -j12 -l12" in "/home/mobiltech/catkin_ws/build"
####
Scanning dependencies of target _pr2_msgs_generate_messages_check_deps_BatteryServer2
Scanning dependencies of target _pr2_msgs_generate_messages_check_deps_GPUStatus
Scanning dependencies of target _pr2_msgs_generate_messages_check_deps_LaserTrajCmd
Scanning dependencies of target geometry_msgs_generate_messages_lisp
Scanning dependencies of target _pr2_msgs_generate_messages_check_deps_BatteryState
Scanning dependencies of target std_msgs_generate_messages_lisp
Scanning dependencies of target _pr2_msgs_generate_messages_check_deps_DashboardState
Scanning dependencies of target _pr2_msgs_generate_messages_check_deps_PowerState
Scanning dependencies of target _pr2_msgs_generate_messages_check_deps_SetLaserTrajCmd
Scanning dependencies of target _pr2_msgs_generate_messages_check_deps_LaserScannerSignal
Scanning dependencies of target _pr2_msgs_generate_messages_check_deps_BatteryState2
Scanning dependencies of target media_files
[  0%] Built target std_msgs_generate_messages_lisp
[  0%] Built target geometry_msgs_generate_messages_lisp
[ 58%] Built target media_files
Scanning dependencies of target _pr2_msgs_generate_messages_check_deps_SetPeriodicCmd
Scanning dependencies of target _pr2_msgs_generate_messages_check_deps_BatteryServer
Scanning dependencies of target _pr2_msgs_generate_messages_check_deps_AccelerometerState
[ 58%] Built target _pr2_msgs_generate_messages_check_deps_DashboardState
[ 58%] Built target _pr2_msgs_generate_messages_check_deps_BatteryServer2
[ 58%] Built target _pr2_msgs_generate_messages_check_deps_LaserTrajCmd
[ 58%] Built target _pr2_msgs_generate_messages_check_deps_PowerState
[ 58%] Built target _pr2_msgs_generate_messages_check_deps_BatteryState
[ 58%] Built target _pr2_msgs_generate_messages_check_deps_SetLaserTrajCmd
[ 58%] Built target _pr2_msgs_generate_messages_check_deps_LaserScannerSignal
[ 58%] Built target ...
(more)
edit retag flag offensive close merge delete

Comments

Hello. I do not think that sourcing the workspace should allow you or not compile correctly. I personally think that the problems is that you maybe you are nottelling cmakelists.txt to build first the messages.

Here you have a solved question on that: https://answers.ros.org/question/7304...

Hope is this!

Solrac3589 gravatar image Solrac3589  ( 2020-06-19 06:54:03 -0500 )edit

Hi @Solrac3589 , thank you for your answer!

Effectively you are right, sourcing the package is completely useless, I will update the title in order to precise the subject of the problem.

In fact my problem is I would like the library I am building to use the service I am creating. The library ndt_func is using the GpsData.srv service, but when I compile the library doesn't find the header.

I don't know which function I should use with which parameter to create the library, I will look further and I hope to find something, anyway thank you for your efficiency!

MCmobil gravatar image MCmobil  ( 2020-06-21 20:02:33 -0500 )edit

That's exaclty what i was thinking that was happening. When you build a project, generally, the messages used (specific in the package) are built creating all the refeered files (including headers) automatically.

The problem appears to be that CmakeLists.txt does not know if he have to build first these messages or the main source files of the project, and as a result, sometimes when you build, it tries to compile the main .cpp files before the messages are build, therefore it does not find the headers of the messages and finally crashes (and that's why when you try several times it seems to be solved magically).

Just telling the CmakeLists.txt to bouild first the messages you avoid this problem

Solrac3589 gravatar image Solrac3589  ( 2020-06-22 01:56:14 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
0

answered 2020-06-21 20:46:02 -0500

MCmobil gravatar image

Fixed! After reading commentary from @Solrac3589

add_dependencies function is working either for creating executable, but also for libraries.

That is to say I add just one line in my CMakeLists under add_libraries like this:

add_library(ndt_func SHARED library/ndt_func.cpp)
add_dependencies(ndt_func ${catkin_EXPORTED_TARGETS})
edit flag offensive delete link more

Comments

Hey! great you find the solution! Sorry to not tell anything before!

Solrac3589 gravatar image Solrac3589  ( 2020-06-22 01:49:14 -0500 )edit

No! You have been helpful enough, your links allowed me to find the solution, that what I was looking for ;)

Thank you one more time!

MCmobil gravatar image MCmobil  ( 2020-06-22 02:00:20 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2020-06-19 03:54:43 -0500

Seen: 644 times

Last updated: Jun 21 '20