Skip to content

Commit

Permalink
Revamp nav2_constrained_smoother to use modern CMake idioms.
Browse files Browse the repository at this point in the history
Signed-off-by: Chris Lalancette <[email protected]>
  • Loading branch information
clalancette committed Jul 31, 2024
1 parent 50e0f7a commit 1c99041
Show file tree
Hide file tree
Showing 5 changed files with 63 additions and 55 deletions.
81 changes: 41 additions & 40 deletions nav2_constrained_smoother/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -4,47 +4,48 @@ project(nav2_constrained_smoother)
set(CMAKE_BUILD_TYPE Release) # significant Ceres optimization speedup

find_package(ament_cmake REQUIRED)
find_package(Ceres REQUIRED COMPONENTS SuiteSparse)
find_package(Eigen3 REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(nav2_core REQUIRED)
find_package(nav2_common REQUIRED)
find_package(angles REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_action REQUIRED)
find_package(nav2_util REQUIRED)
find_package(nav2_msgs REQUIRED)
find_package(nav2_costmap_2d REQUIRED)
find_package(nav2_msgs REQUIRED)
find_package(nav2_util REQUIRED)
find_package(pluginlib REQUIRED)
find_package(Ceres REQUIRED COMPONENTS SuiteSparse)

set(CMAKE_CXX_STANDARD 17)

if(${CERES_VERSION} VERSION_LESS_EQUAL 2.0.0)
add_definitions(-DUSE_OLD_CERES_API)
endif()
find_package(rclcpp REQUIRED)
find_package(rclcpp_lifecycle REQUIRED)
find_package(tf2_ros REQUIRED)

nav2_package()

set(library_name nav2_constrained_smoother)

include_directories(
include
add_library(${library_name} SHARED src/constrained_smoother.cpp)
if(${CERES_VERSION} VERSION_LESS_EQUAL 2.0.0)
target_compile_definitions(${library_name} PUBLIC -DUSE_OLD_CERES_API)
endif()
target_include_directories(${library_name}
PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
)

set(dependencies
angles
rclcpp
rclcpp_action
nav2_msgs
nav2_costmap_2d
nav2_util
nav2_core
pluginlib
target_link_libraries(${library_name} PUBLIC
Ceres::ceres
Eigen3::Eigen
nav2_core::nav2_core
nav2_costmap_2d::nav2_costmap_2d_client
nav2_costmap_2d::nav2_costmap_2d_core
nav2_util::nav2_util_core
rclcpp::rclcpp
rclcpp_lifecycle::rclcpp_lifecycle
tf2_ros::tf2_ros
)
target_link_libraries(${library_name} PRIVATE
${geometry_msgs_TARGETS}
${nav_msgs_TARGETS}
pluginlib::pluginlib
)

add_library(${library_name} SHARED src/constrained_smoother.cpp)
target_link_libraries(${library_name} Ceres::ceres)
# prevent pluginlib from using boost
target_compile_definitions(${library_name} PUBLIC "PLUGINLIB__DISABLE_BOOST_FUNCTIONS")
ament_target_dependencies(${library_name} ${dependencies})

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
Expand All @@ -53,29 +54,29 @@ if(BUILD_TESTING)
ament_lint_auto_find_test_dependencies()

find_package(ament_cmake_gtest REQUIRED)
find_package(angles REQUIRED)

ament_find_gtest()

add_subdirectory(test)
endif()

install(
TARGETS
${library_name}
TARGETS ${library_name}
EXPORT ${library_name}
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
)

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

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
endif()

ament_export_include_directories(include)
ament_export_include_directories(include/${PROJECT_NAME})
ament_export_libraries(${library_name})
ament_export_dependencies(${dependencies})
ament_export_dependencies(ceres eigen3 nav2_core nav2_costmap_2d nav2_util rclcpp rclcpp_lifecycle tf2_ros)
ament_export_targets(${library_name})

pluginlib_export_plugin_description_file(nav2_core nav2_constrained_smoother.xml)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,6 @@
#include "rclcpp/rclcpp.hpp"
#include "nav2_util/odometry_utils.hpp"
#include "nav2_util/geometry_utils.hpp"
#include "geometry_msgs/msg/pose2_d.hpp"

namespace nav2_constrained_smoother
{
Expand Down
19 changes: 12 additions & 7 deletions nav2_constrained_smoother/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -9,20 +9,25 @@
<license>Apache-2.0</license>

<buildtool_depend>ament_cmake</buildtool_depend>
<depend>nav2_common</depend>
<depend>angles</depend>
<depend>rclcpp</depend>
<depend>nav2_util</depend>
<depend>nav2_msgs</depend>
<depend>nav2_costmap_2d</depend>
<build_depend>eigen</build_depend>
<build_depend>nav2_common</build_depend>

<depend>geometry_msgs</depend>
<depend>libceres-dev</depend>
<depend>nav2_core</depend>
<depend>nav2_costmap_2d</depend>
<depend>nav2_msgs</depend>
<depend>nav2_util</depend>
<depend>pluginlib</depend>
<depend>libceres-dev</depend>
<depend>rclcpp</depend>
<depend>rclcpp_lifecycle</depend>
<depend>tf2_ros</depend>

<test_depend>ament_lint_common</test_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_cmake_gtest</test_depend>
<test_depend>ament_cmake_pytest</test_depend>
<test_depend>angles</test_depend>

<export>
<build_type>ament_cmake</build_type>
Expand Down
2 changes: 2 additions & 0 deletions nav2_constrained_smoother/src/constrained_smoother.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,8 @@
#include <utility>
#include <vector>

#include "geometry_msgs/msg/pose_stamped.hpp"

#include "nav2_constrained_smoother/constrained_smoother.hpp"
#include "nav2_util/node_utils.hpp"
#include "nav2_util/geometry_utils.hpp"
Expand Down
15 changes: 8 additions & 7 deletions nav2_constrained_smoother/test/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,20 +1,21 @@
ament_add_gtest(test_constrained_smoother
test_constrained_smoother.cpp
)

target_link_libraries(test_constrained_smoother
${library_name}
)
ament_target_dependencies(test_constrained_smoother
${dependencies}
angles::angles
${geometry_msgs_TARGETS}
nav2_costmap_2d::nav2_costmap_2d_client
nav2_costmap_2d::nav2_costmap_2d_core
nav2_util::nav2_util_core
rclcpp::rclcpp
tf2_ros::tf2_ros
)

ament_add_gtest(test_smoother_cost_function
test_smoother_cost_function.cpp
)
target_link_libraries(test_smoother_cost_function
${library_name}
rclcpp::rclcpp
)
ament_target_dependencies(test_smoother_cost_function
${dependencies}
)

0 comments on commit 1c99041

Please sign in to comment.