Skip to content

Commit

Permalink
Remove nav2_util dependency
Browse files Browse the repository at this point in the history
Signed-off-by: Alberto Tudela <ajtudela@gmail.com>
  • Loading branch information
ajtudela committed Jun 12, 2024
1 parent 240de9e commit 0e55393
Show file tree
Hide file tree
Showing 7 changed files with 48 additions and 42 deletions.
8 changes: 6 additions & 2 deletions CHANGELOG.rst
Original file line number Diff line number Diff line change
@@ -1,6 +1,10 @@
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
Changelog for package laser_segmentation
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

3.0.1 (12-06-2024)
------------------
* Remove nav2_util dependency.

3.0.0 (08-03-2024)
------------------
Expand Down
4 changes: 2 additions & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -50,11 +50,11 @@ endif()
# # Find ament macros and libraries
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_lifecycle REQUIRED)
find_package(rclcpp_components REQUIRED)
find_package(std_msgs REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(visualization_msgs REQUIRED)
find_package(nav2_util REQUIRED)
find_package(slg_msgs REQUIRED) # formerly simple_laser_geometry

# ##########
Expand All @@ -75,11 +75,11 @@ set(source

set(dependencies
rclcpp
rclcpp_lifecycle
rclcpp_components
std_msgs
sensor_msgs
visualization_msgs
nav2_util
slg_msgs
)

Expand Down
22 changes: 21 additions & 1 deletion include/laser_segmentation/parameter_handler.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,6 @@

#include "rclcpp/rclcpp.hpp"
#include "rclcpp_lifecycle/lifecycle_node.hpp"
#include "nav2_util/node_utils.hpp"

namespace laser_segmentation
{
Expand Down Expand Up @@ -74,6 +73,27 @@ class ParameterHandler
rcl_interfaces::msg::SetParametersResult
dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters);

/**
* @brief Declares static ROS2 parameter and sets it to a given value if it was not already declared.
*
* @param node A node in which given parameter to be declared
* @param param_name The name of parameter
* @param default_value Parameter value to initialize with
* @param parameter_descriptor Parameter descriptor (optional)
*/
template<typename NodeT>
void declare_parameter_if_not_declared(
NodeT node,
const std::string & param_name,
const rclcpp::ParameterValue & default_value,
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
rcl_interfaces::msg::ParameterDescriptor())
{
if (!node->has_parameter(param_name)) {
node->declare_parameter(param_name, default_value, parameter_descriptor);
}
}

// Dynamic parameters handler
std::mutex mutex_;
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
Expand Down
4 changes: 2 additions & 2 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,19 +2,19 @@
<?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.0</version>
<version>3.0.1</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>
<license>Apache-2.0</license>
<author email="ajtudela@gmail.com">Alberto Tudela</author>
<buildtool_depend>ament_cmake</buildtool_depend>
<depend>rclcpp</depend>
<depend>rclcpp_lifecycle</depend>
<depend>rclcpp_components</depend>
<depend>std_msgs</depend>
<depend>sensor_msgs</depend>
<depend>visualization_msgs</depend>
<depend>nav2_util</depend>
<depend>slg_msgs</depend> <!-- formerly simple_laser_geometry -->

<test_depend>ament_lint_auto</test_depend>
Expand Down
19 changes: 6 additions & 13 deletions src/parameter_handler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,12 +24,10 @@
namespace laser_segmentation
{

using nav2_util::declare_parameter_if_not_declared;
using rcl_interfaces::msg::ParameterType;

ParameterHandler::ParameterHandler(
rclcpp_lifecycle::LifecycleNode::SharedPtr node,
const rclcpp::Logger & logger)
rclcpp_lifecycle::LifecycleNode::SharedPtr node, const rclcpp::Logger & logger)
{
logger_ = logger;

Expand Down Expand Up @@ -146,13 +144,11 @@ ParameterHandler::ParameterHandler(

node->get_parameter("min_points_segment", params_.min_points_segment);
RCLCPP_INFO(
logger_, "The parameter min_points_segment is set to: [%d]",
params_.min_points_segment);
logger_, "The parameter min_points_segment is set to: [%d]", params_.min_points_segment);

node->get_parameter("max_points_segment", params_.max_points_segment);
RCLCPP_INFO(
logger_, "The parameter max_points_segment is set to: [%d]",
params_.max_points_segment);
logger_, "The parameter max_points_segment is set to: [%d]", params_.max_points_segment);

node->get_parameter("min_avg_distance_from_sensor", params_.min_avg_distance_from_sensor);
RCLCPP_INFO(
Expand All @@ -178,8 +174,7 @@ ParameterHandler::ParameterHandler(

node->get_parameter("noise_reduction", params_.noise_reduction);
RCLCPP_INFO(
logger_, "The parameter noise_reduction is set to: [%f]",
params_.noise_reduction);
logger_, "The parameter noise_reduction is set to: [%f]", params_.noise_reduction);

node->get_parameter("method_threshold", params_.method_threshold);
RCLCPP_INFO(
Expand All @@ -190,13 +185,11 @@ ParameterHandler::ParameterHandler(

node->get_parameter("segments_topic", params_.seg_topic);
RCLCPP_INFO(
logger_, "The parameter segment_topic is set to: [%s]",
params_.seg_topic.c_str());
logger_, "The parameter segment_topic is set to: [%s]", params_.seg_topic.c_str());

node->get_parameter("segmentation_type", params_.segmentation_type);
RCLCPP_INFO(
logger_, "The parameter segmentation_type is set to: [%s]",
params_.segmentation_type.c_str());
logger_, "The parameter segmentation_type is set to: [%s]", params_.segmentation_type.c_str());

dyn_params_handler_ = node->add_on_set_parameters_callback(
std::bind(&ParameterHandler::dynamicParametersCallback, this, std::placeholders::_1));
Expand Down
6 changes: 2 additions & 4 deletions test/test_integration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,10 +34,8 @@ TEST(LaserSegmentationTest, integration) {
// Create and configure the laser_segmentation node
auto seg_node = std::make_shared<laser_segmentation::LaserSegmentation>();
// Set some parameters
nav2_util::declare_parameter_if_not_declared(
seg_node, "min_points_segment", rclcpp::ParameterValue(1));
nav2_util::declare_parameter_if_not_declared(
seg_node, "max_points_segment", rclcpp::ParameterValue(3));
seg_node->declare_parameter("min_points_segment", rclcpp::ParameterValue(1));
seg_node->declare_parameter("max_points_segment", rclcpp::ParameterValue(3));
seg_node->configure();
seg_node->activate();

Expand Down
27 changes: 9 additions & 18 deletions test/test_laser_segmentation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,8 +53,7 @@ TEST(LaserSegmentationTest, configure) {
// Create the node
auto node = std::make_shared<laserSegmentationFixture>();
// Set the default segmentation type "jump_distance"
nav2_util::declare_parameter_if_not_declared(
node, "segmentation_type", rclcpp::ParameterValue("jump_distance"));
node->declare_parameter("segmentation_type", rclcpp::ParameterValue("jump_distance"));
node->configure();
node->activate();
// Call an empty callback
Expand Down Expand Up @@ -211,22 +210,14 @@ TEST(LaserSegmentationTest, filterSegments) {
// Create the node
auto node = std::make_shared<laserSegmentationFixture>();
// Set the parameters
nav2_util::declare_parameter_if_not_declared(
node, "min_points_segment", rclcpp::ParameterValue(1));
nav2_util::declare_parameter_if_not_declared(
node, "max_points_segment", rclcpp::ParameterValue(3));
nav2_util::declare_parameter_if_not_declared(
node, "min_avg_distance_from_sensor", rclcpp::ParameterValue(1.0));
nav2_util::declare_parameter_if_not_declared(
node, "max_avg_distance_from_sensor", rclcpp::ParameterValue(10.0));
nav2_util::declare_parameter_if_not_declared(
node, "min_segment_width", rclcpp::ParameterValue(0.1));
nav2_util::declare_parameter_if_not_declared(
node, "max_segment_width", rclcpp::ParameterValue(10.0));
nav2_util::declare_parameter_if_not_declared(
node, "distance_threshold", rclcpp::ParameterValue(0.1));
nav2_util::declare_parameter_if_not_declared(
node, "noise_reduction", rclcpp::ParameterValue(0.1));
node->declare_parameter("min_points_segment", rclcpp::ParameterValue(1));
node->declare_parameter("max_points_segment", rclcpp::ParameterValue(3));
node->declare_parameter("min_avg_distance_from_sensor", rclcpp::ParameterValue(1.0));
node->declare_parameter("max_avg_distance_from_sensor", rclcpp::ParameterValue(10.0));
node->declare_parameter("min_segment_width", rclcpp::ParameterValue(0.1));
node->declare_parameter("max_segment_width", rclcpp::ParameterValue(10.0));
node->declare_parameter("distance_threshold", rclcpp::ParameterValue(0.1));
node->declare_parameter("noise_reduction", rclcpp::ParameterValue(0.1));
node->configure();

// Set a segment list with 0 segments
Expand Down

0 comments on commit 0e55393

Please sign in to comment.