Skip to content

Commit

Permalink
Add thread find_package
Browse files Browse the repository at this point in the history
  • Loading branch information
Acuadros95 committed Jan 20, 2022
1 parent 5435537 commit 196d0f9
Show file tree
Hide file tree
Showing 4 changed files with 4 additions and 1 deletion.
1 change: 1 addition & 0 deletions rclc/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@ find_package(rcl_action REQUIRED)
find_package(rcutils REQUIRED)
find_package(rosidl_generator_c REQUIRED)
find_package(std_msgs REQUIRED)
find_package(Threads REQUIRED)

if("${rcl_VERSION}" VERSION_LESS "1.0.0")
message(STATUS
Expand Down
1 change: 1 addition & 0 deletions rclc_examples/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@ find_package(std_msgs REQUIRED)
find_package(lifecycle_msgs REQUIRED)
find_package(example_interfaces REQUIRED)
find_package(rclc_parameter REQUIRED)
find_package(Threads REQUIRED)

include_directories(include)

Expand Down
2 changes: 1 addition & 1 deletion rclc_lifecycle/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ find_package(std_msgs REQUIRED)
find_package(lifecycle_msgs REQUIRED)
find_package(rcl_lifecycle REQUIRED)
find_package(rclc REQUIRED)

find_package(Threads REQUIRED)

if("${rcl_lifecycle_VERSION}" VERSION_LESS "1.0.0")
message(STATUS "Found rcl_lifecycle version ${rcl_lifecycle_VERSION}, which belongs to Eloquent or earlier")
Expand Down
1 change: 1 addition & 0 deletions rclc_parameter/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@ find_package(rcutils REQUIRED)
find_package(builtin_interfaces REQUIRED)
find_package(rcl_interfaces REQUIRED)
find_package(rosidl_runtime_c REQUIRED)
find_package(Threads REQUIRED)

#################################################
# create library
Expand Down

0 comments on commit 196d0f9

Please sign in to comment.