Skip to content

Commit

Permalink
Update to use modern CMake idioms
Browse files Browse the repository at this point in the history
Signed-off-by: Alberto Tudela <ajtudela@gmail.com>
  • Loading branch information
ajtudela committed Jul 31, 2024
1 parent a8d3b88 commit a63f9e9
Show file tree
Hide file tree
Showing 6 changed files with 15 additions and 14 deletions.
4 changes: 4 additions & 0 deletions CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,10 @@
Changelog for package laser_segmentation
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

3.0.2 (31-07-2024)
------------------
* Update to use modern CMake idioms.

3.0.1 (12-06-2024)
------------------
* Remove nav2_util dependency.
Expand Down
14 changes: 5 additions & 9 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -77,27 +77,22 @@ target_include_directories(${library_name}
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>")
target_link_libraries(${library_name}
PUBLIC
rclcpp::rclcpp
rclcpp_lifecycle::rclcpp_lifecycle
${rclcpp_components_TARGETS}
${sensor_msgs_TARGETS}
${slg_msgs_TARGETS}
slg_msgs::slg_core
${visualization_msgs_TARGETS}
PRIVATE
rclcpp::rclcpp
rclcpp_components::component
)

# Add executables
add_executable(${PROJECT_NAME} src/main.cpp)
target_include_directories(${PROJECT_NAME}
PUBLIC
"$<BUILD_INTERFACE:${CMAKE_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>")
target_link_libraries(${PROJECT_NAME}
PUBLIC
rclcpp_lifecycle::rclcpp_lifecycle
PRIVATE
rclcpp::rclcpp
${library_name}
rclcpp::rclcpp
)

rclcpp_components_register_nodes(${library_name} "laser_segmentation::LaserSegmentation")
Expand All @@ -106,6 +101,7 @@ rclcpp_components_register_nodes(${library_name} "laser_segmentation::LaserSegme
# # Install ##
# ############
install(TARGETS ${library_name}
EXPORT ${library_name}
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
Expand Down
3 changes: 1 addition & 2 deletions include/laser_segmentation/laser_segmentation.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -129,8 +129,7 @@ class LaserSegmentation : public rclcpp_lifecycle::LifecycleNode
* @return slg_msgs::msg::SegmentArray The segment array message
*/
visualization_msgs::msg::MarkerArray create_segment_viz_points(
std_msgs::msg::Header header,
std::vector<slg::Segment2D> segment_list);
std_msgs::msg::Header header, std::vector<slg::Segment2D> segment_list);

/**
* @brief Get the parula color object
Expand Down
4 changes: 3 additions & 1 deletion include/laser_segmentation/parameter_handler.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,8 +19,10 @@
#include <string>
#include <vector>

#include "rclcpp/rclcpp.hpp"
#include "rclcpp/logger.hpp"
#include "rclcpp/parameter.hpp"
#include "rclcpp_lifecycle/lifecycle_node.hpp"
#include "rcl_interfaces/msg/set_parameters_result.hpp"

namespace laser_segmentation
{
Expand Down
2 changes: 1 addition & 1 deletion package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>laser_segmentation</name>
<version>3.0.1</version>
<version>3.0.2</version>
<description>Implementation of algorithms for segmentation of laserscans.</description>
<maintainer email="ajtudela@gmail.com">Alberto Tudela</maintainer>
<maintainer email="manolofc@gmail.com">Manuel Fernandez-Carmona</maintainer>
Expand Down
2 changes: 1 addition & 1 deletion test/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
# Test for segmentations algorithm
ament_add_gtest(test_segmentations test_segmentations.cpp)
target_link_libraries(test_segmentations ${library_name} ${slg_msgs_TARGETS})
target_link_libraries(test_segmentations ${library_name} slg_msgs::slg_core)

# Test for laser_segmentation
ament_add_gtest(test_laser_segmentation test_laser_segmentation.cpp)
Expand Down

0 comments on commit a63f9e9

Please sign in to comment.