Skip to content

Commit

Permalink
Improve compile time (#2)
Browse files Browse the repository at this point in the history
* Link libraries as _TARGETS

Signed-off-by: Yadunund <yadunund@openrobotics.org>

* Update README

Signed-off-by: Yadunund <yadunund@openrobotics.org>

---------

Signed-off-by: Yadunund <yadunund@openrobotics.org>
  • Loading branch information
Yadunund authored Aug 23, 2023
1 parent ce0ad6b commit 0f5940a
Show file tree
Hide file tree
Showing 7 changed files with 33 additions and 44 deletions.
13 changes: 1 addition & 12 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -13,15 +13,6 @@ For details on architecture and concepts [see](./docs/concepts.md).

## Setup

### Install system dependencies
It is recommended to build the workspace with clang as compiler and lld as linker.
Hence we install these dependencies along with some `colcon-mixin` shortcuts to simplify build instructions.
```bash
sudo apt update && sudo apt install -y clang clang-tools lld libstdc++-12-dev
colcon mixin add default https://raw.githubusercontent.com/colcon/colcon-mixin-repository/master/index.yaml
colcon mixin update default
```

### Setup the NEXUS workspace

```bash
Expand All @@ -35,10 +26,8 @@ rosdep install --from-paths src --ignore-src --rosdistro humble -y -r

### Build the NEXUS workspace
```bash
export CX=clang
export CXX=clang++
source /opt/ros/humble/setup.bash
colcon build --mixin release lld
colcon build --cmake-args -DCMAKE_BUILD_TYPE=Release
```

## Configuration
Expand Down
4 changes: 2 additions & 2 deletions nexus_capabilities/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -74,8 +74,8 @@ target_link_libraries(${PROJECT_NAME}
PUBLIC
nexus_common::nexus_common
nexus_endpoints::nexus_endpoints
${geometry_msgs_LIBRARIES}
${nexus_orchestrator_msgs_LIBRARIES}
${geometry_msgs_TARGETS}
${nexus_orchestrator_msgs_TARGETS}
BT::behaviortree_cpp_v3
rclcpp::rclcpp
rclcpp_lifecycle::rclcpp_lifecycle
Expand Down
10 changes: 5 additions & 5 deletions nexus_common/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -43,9 +43,9 @@ target_link_libraries(${PROJECT_NAME} PUBLIC
rclcpp_lifecycle::rclcpp_lifecycle
tf2::tf2
yaml-cpp
${lifecycle_msgs_LIBRARIES}
${geometry_msgs_LIBRARIES}
${vision_msgs_LIBRARIES}
${lifecycle_msgs_TARGETS}
${geometry_msgs_TARGETS}
${vision_msgs_TARGETS}
)
set_target_properties(${PROJECT_NAME} PROPERTIES CXX_VISIBILITY_PRESET hidden)
target_compile_features(${PROJECT_NAME} PUBLIC cxx_std_17)
Expand Down Expand Up @@ -111,8 +111,8 @@ if(BUILD_TESTING)
rclcpp_action::rclcpp_action
BT::behaviortree_cpp_v3
rmf_utils::rmf_utils
${example_interfaces_LIBRARIES}
${std_msgs_LIBRARIES}
${example_interfaces_TARGETS}
${std_msgs_TARGETS}
)
endfunction()

Expand Down
18 changes: 9 additions & 9 deletions nexus_endpoints/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -29,15 +29,15 @@ target_include_directories(nexus_endpoints INTERFACE
${trajectory_msgs_INCLUDE_DIRS}
)
target_link_libraries(nexus_endpoints INTERFACE rclcpp::rclcpp rclcpp_action::rclcpp_action
${control_msgs_LIBRARIES}
${nexus_alarm_msgs_LIBRARIES}
${nexus_calibration_msgs_LIBRARIES}
${nexus_detector_msgs_LIBRARIES}
${nexus_dispenser_msgs_LIBRARIES}
${nexus_motion_planner_msgs_LIBRARIES}
${nexus_orchestrator_msgs_LIBRARIES}
${nexus_transporter_msgs_LIBRARIES}
${trajectory_msgs_LIBRARIES}
${control_msgs_TARGETS}
${nexus_alarm_msgs_TARGETS}
${nexus_calibration_msgs_TARGETS}
${nexus_detector_msgs_TARGETS}
${nexus_dispenser_msgs_TARGETS}
${nexus_motion_planner_msgs_TARGETS}
${nexus_orchestrator_msgs_TARGETS}
${nexus_transporter_msgs_TARGETS}
${trajectory_msgs_TARGETS}
)
set_target_properties(nexus_endpoints PROPERTIES PUBLIC_HEADER nexus_endpoints.hpp)

Expand Down
12 changes: 6 additions & 6 deletions nexus_integration_tests/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -34,8 +34,8 @@ target_link_libraries(mock_detection PRIVATE
nexus_endpoints::nexus_endpoints
rclcpp::rclcpp
rclcpp_lifecycle::rclcpp_lifecycle
${yaml_cpp_vendor_LIBRARIES}
${tf2_ros_LIBRARIES}
${yaml_cpp_vendor_TARGETS}
${tf2_ros_TARGETS}
)
target_include_directories(mock_detection PRIVATE
${tf2_ros_INCLUDE_DIRS}
Expand All @@ -48,7 +48,7 @@ add_library(mock_emergency_alarm_component SHARED src/mock_emergency_alarm.cpp)
target_link_libraries(mock_emergency_alarm_component
nexus_endpoints::nexus_endpoints
rclcpp::rclcpp
${rclcpp_components_LIBRARIES}
${rclcpp_components_TARGETS}
rclcpp_lifecycle::rclcpp_lifecycle
)
ament_target_dependencies(mock_emergency_alarm_component
Expand Down Expand Up @@ -93,7 +93,7 @@ target_link_libraries(mock_printer PRIVATE
nexus_endpoints::nexus_endpoints
rclcpp::rclcpp
rclcpp_lifecycle::rclcpp_lifecycle
${rclcpp_components_LIBRARIES}
${rclcpp_components_TARGETS}
)
target_compile_features(mock_printer INTERFACE cxx_std_17)
rclcpp_components_register_node(mock_printer
Expand Down Expand Up @@ -163,9 +163,9 @@ if(BUILD_TESTING)
rclcpp_action::rclcpp_action
rclcpp_lifecycle::rclcpp_lifecycle
rcpputils::rcpputils
${yaml_cpp_vendor_LIBRARIES}
${yaml_cpp_vendor_TARGETS}
rmf_utils::rmf_utils
${tf2_ros_LIBRARIES}
${tf2_ros_TARGETS}
)
target_include_directories(test_mocks PUBLIC
${yaml_cpp_vendor_INCLUDE_DIRS}
Expand Down
16 changes: 8 additions & 8 deletions nexus_transporter/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -32,10 +32,10 @@ add_library(nexus_transporter SHARED

target_link_libraries(nexus_transporter
PUBLIC
${nexus_transporter_msgs_LIBRARIES}
${nexus_transporter_msgs_TARGETS}
rclcpp::rclcpp
${rclcpp_action_LIBRARIES}
${rclcpp_lifecycle_LIBRARIES}
${rclcpp_action_TARGETS}
${rclcpp_lifecycle_TARGETS}
rmf_utils::rmf_utils
)

Expand All @@ -61,13 +61,13 @@ target_link_libraries(nexus_transporter_component
PUBLIC
nexus_endpoints::nexus_endpoints
nexus_transporter
${nexus_transporter_msgs_LIBRARIES}
${geometry_msgs_LIBRARIES}
${nexus_transporter_msgs_TARGETS}
${geometry_msgs_TARGETS}
pluginlib::pluginlib
rclcpp::rclcpp
${rclcpp_components_LIBRARIES}
${rclcpp_lifecycle_LIBRARIES}
${tf2_ros_LIBRARIES}
${rclcpp_components_TARGETS}
${rclcpp_lifecycle_TARGETS}
${tf2_ros_TARGETS}
)

target_include_directories(nexus_transporter_component
Expand Down
4 changes: 2 additions & 2 deletions nexus_workcell_orchestrator/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -57,8 +57,8 @@ target_link_libraries(${PROJECT_NAME}_plugin PUBLIC
tf2::tf2
tf2_ros::tf2_ros
yaml-cpp
${vision_msgs_LIBRARIES}
${geometry_msgs_LIBRARIES}
${vision_msgs_TARGETS}
${geometry_msgs_TARGETS}
)
target_compile_features(${PROJECT_NAME}_plugin PUBLIC cxx_std_17)
target_compile_definitions(${PROJECT_NAME}_plugin PUBLIC "COMPOSITION_BUILDING_DLL")
Expand Down

0 comments on commit 0f5940a

Please sign in to comment.