Skip to content

Commit 0082e1a

Browse files
committed
Added namespace
Signed-off-by: Alberto Tudela <[email protected]>
1 parent c6ba19b commit 0082e1a

15 files changed

+83
-28
lines changed

CMakeLists.txt

+1-1
Original file line numberDiff line numberDiff line change
@@ -66,7 +66,7 @@ add_library(${library_name} SHARED ${source})
6666
ament_target_dependencies(${library_name} ${dependencies})
6767
target_link_libraries(${library_name})
6868

69-
rclcpp_components_register_nodes(${library_name} "composition::LaserSegmentation")
69+
rclcpp_components_register_nodes(${library_name} "laser_segmentation::LaserSegmentation")
7070

7171
# ############
7272
# # Install ##

include/laser_segmentation/laser_segmentation.hpp

+13-3
Original file line numberDiff line numberDiff line change
@@ -41,21 +41,29 @@
4141

4242
using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
4343

44-
class laserSegmentation : public rclcpp_lifecycle::LifecycleNode
44+
namespace laser_segmentation
45+
{
46+
47+
/**
48+
* @brief laser_segmentation::LaserSegmentation class is a ROS2 node that subscribes to a laser scan
49+
* topic and publishes the segments found in the scan.
50+
*
51+
*/
52+
class LaserSegmentation : public rclcpp_lifecycle::LifecycleNode
4553
{
4654
public:
4755
/**
4856
* @brief Construct a new laser Segmentation object
4957
*
5058
* @param options Node options
5159
*/
52-
explicit laserSegmentation(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
60+
explicit LaserSegmentation(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
5361

5462
/**
5563
* @brief Destroy the laser Segmentation object
5664
*
5765
*/
58-
~laserSegmentation() = default;
66+
~LaserSegmentation() = default;
5967

6068
/**
6169
* @brief Configure the node
@@ -151,4 +159,6 @@ class laserSegmentation : public rclcpp_lifecycle::LifecycleNode
151159
std::shared_ptr<Segmentation> segmentation_;
152160
};
153161

162+
} // namespace laser_segmentation
163+
154164
#endif // LASER_SEGMENTATION__LASER_SEGMENTATION_HPP_

include/laser_segmentation/parameter_handler.hpp

+5
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,9 @@
2525
#include "rclcpp_lifecycle/lifecycle_node.hpp"
2626
#include "nav2_util/node_utils.hpp"
2727

28+
namespace laser_segmentation
29+
{
30+
2831
struct Parameters
2932
{
3033
int min_points_segment;
@@ -78,4 +81,6 @@ class ParameterHandler
7881
rclcpp::Logger logger_ {rclcpp::get_logger("laser_segmentation")};
7982
};
8083

84+
} // namespace laser_segmentation
85+
8186
#endif // LASER_SEGMENTATION__PARAMETER_HANDLER_HPP_

include/laser_segmentation/parula.hpp

+5
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,9 @@
1515
#ifndef LASER_SEGMENTATION__PARULA_HPP_
1616
#define LASER_SEGMENTATION__PARULA_HPP_
1717

18+
namespace laser_segmentation
19+
{
20+
1821
float parula[256][3] = {
1922
{0.2081, 0.1663, 0.5292},
2023
{0.2091, 0.1721, 0.5411},
@@ -273,4 +276,6 @@ float parula[256][3] = {
273276
{0.9736, 0.9752, 0.0597},
274277
{0.9763, 0.9831, 0.0538}};
275278

279+
} // namespace laser_segmentation
280+
276281
#endif // LASER_SEGMENTATION__PARULA_HPP_

include/laser_segmentation/segmentation/jump_distance.hpp

+5
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,9 @@
2222

2323
#include "laser_segmentation/segmentation/segmentation.hpp"
2424

25+
namespace laser_segmentation
26+
{
27+
2528
/**
2629
* @brief Classic jump distance segmentation algorithm.
2730
*
@@ -138,4 +141,6 @@ class JumpDistanceSegmentation : public Segmentation
138141
std::string threshold_method_;
139142
};
140143

144+
} // namespace laser_segmentation
145+
141146
#endif // LASER_SEGMENTATION__SEGMENTATION__JUMP_DISTANCE_HPP_

include/laser_segmentation/segmentation/jump_distance_merge.hpp

+5
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,9 @@
2222

2323
#include "laser_segmentation/segmentation/jump_distance.hpp"
2424

25+
namespace laser_segmentation
26+
{
27+
2528
/**
2629
* @brief Jump distance segmentation algorithm which merge segments
2730
* by checking against the last point of preceding segments.
@@ -69,4 +72,6 @@ class JumpDistanceSegmentationMerge : public JumpDistanceSegmentation
6972
typedef std::shared_ptr<JumpDistanceSegmentationMerge> SharedPtr;
7073
};
7174

75+
} // namespace laser_segmentation
76+
7277
#endif // LASER_SEGMENTATION__SEGMENTATION__JUMP_DISTANCE_MERGE_HPP_

include/laser_segmentation/segmentation/segmentation.hpp

+5
Original file line numberDiff line numberDiff line change
@@ -24,6 +24,9 @@
2424
#include "slg_msgs/point2D.hpp"
2525
#include "slg_msgs/segment2D.hpp"
2626

27+
namespace laser_segmentation
28+
{
29+
2730
/**
2831
* @brief Abstract class for a generic segmentation algorithm.
2932
*
@@ -74,4 +77,6 @@ class Segmentation
7477
}
7578
};
7679

80+
} // namespace laser_segmentation
81+
7782
#endif // LASER_SEGMENTATION__SEGMENTATION__SEGMENTATION_HPP_

src/laser_segmentation.cpp

+18-13
Original file line numberDiff line numberDiff line change
@@ -14,12 +14,15 @@
1414

1515
#include "laser_segmentation/laser_segmentation.hpp"
1616

17-
laserSegmentation::laserSegmentation(const rclcpp::NodeOptions & options)
17+
namespace laser_segmentation
18+
{
19+
20+
LaserSegmentation::LaserSegmentation(const rclcpp::NodeOptions & options)
1821
: rclcpp_lifecycle::LifecycleNode("laser_segmentation", "", options)
1922
{
2023
}
2124

22-
CallbackReturn laserSegmentation::on_configure(const rclcpp_lifecycle::State &)
25+
CallbackReturn LaserSegmentation::on_configure(const rclcpp_lifecycle::State &)
2326
{
2427
// Handles storage and dynamic configuration of parameters.
2528
// Returns pointer to data current param settings.
@@ -48,14 +51,14 @@ CallbackReturn laserSegmentation::on_configure(const rclcpp_lifecycle::State &)
4851
scan_sub_ = this->create_subscription<sensor_msgs::msg::LaserScan>(
4952
params_->scan_topic,
5053
default_qos,
51-
std::bind(&laserSegmentation::scan_callback, this, std::placeholders::_1));
54+
std::bind(&LaserSegmentation::scan_callback, this, std::placeholders::_1));
5255

5356
RCLCPP_INFO(this->get_logger(), "Configured laser segmentation node");
5457

5558
return CallbackReturn::SUCCESS;
5659
}
5760

58-
CallbackReturn laserSegmentation::on_activate(const rclcpp_lifecycle::State & state)
61+
CallbackReturn LaserSegmentation::on_activate(const rclcpp_lifecycle::State & state)
5962
{
6063
LifecycleNode::on_activate(state);
6164
RCLCPP_INFO(this->get_logger(), "Activating the node...");
@@ -65,7 +68,7 @@ CallbackReturn laserSegmentation::on_activate(const rclcpp_lifecycle::State & st
6568
return CallbackReturn::SUCCESS;
6669
}
6770

68-
CallbackReturn laserSegmentation::on_deactivate(const rclcpp_lifecycle::State & state)
71+
CallbackReturn LaserSegmentation::on_deactivate(const rclcpp_lifecycle::State & state)
6972
{
7073
LifecycleNode::on_deactivate(state);
7174
RCLCPP_INFO(this->get_logger(), "Deactivating the node...");
@@ -75,7 +78,7 @@ CallbackReturn laserSegmentation::on_deactivate(const rclcpp_lifecycle::State &
7578
return CallbackReturn::SUCCESS;
7679
}
7780

78-
CallbackReturn laserSegmentation::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
81+
CallbackReturn LaserSegmentation::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
7982
{
8083
RCLCPP_INFO(this->get_logger(), "Cleaning the node...");
8184

@@ -87,7 +90,7 @@ CallbackReturn laserSegmentation::on_cleanup(const rclcpp_lifecycle::State & /*s
8790
return CallbackReturn::SUCCESS;
8891
}
8992

90-
CallbackReturn laserSegmentation::on_shutdown(const rclcpp_lifecycle::State & state)
93+
CallbackReturn LaserSegmentation::on_shutdown(const rclcpp_lifecycle::State & state)
9194
{
9295
RCLCPP_INFO(this->get_logger(), "Shutdown the node from state %s.", state.label().c_str());
9396

@@ -98,7 +101,7 @@ CallbackReturn laserSegmentation::on_shutdown(const rclcpp_lifecycle::State & st
98101
return CallbackReturn::SUCCESS;
99102
}
100103

101-
void laserSegmentation::scan_callback(const sensor_msgs::msg::LaserScan::SharedPtr scan_msg)
104+
void LaserSegmentation::scan_callback(const sensor_msgs::msg::LaserScan::SharedPtr scan_msg)
102105
{
103106
std::lock_guard<std::mutex> param_lock(param_handler_->getMutex());
104107

@@ -156,7 +159,7 @@ void laserSegmentation::scan_callback(const sensor_msgs::msg::LaserScan::SharedP
156159
create_segment_viz_points(scan_msg->header, segment_filtered_list));
157160
}
158161

159-
std::vector<slg::Segment2D> laserSegmentation::filter_segments(
162+
std::vector<slg::Segment2D> LaserSegmentation::filter_segments(
160163
const std::vector<slg::Segment2D> & segments)
161164
{
162165
std::vector<slg::Segment2D> filtered_segments;
@@ -192,7 +195,7 @@ std::vector<slg::Segment2D> laserSegmentation::filter_segments(
192195
return filtered_segments;
193196
}
194197

195-
visualization_msgs::msg::MarkerArray laserSegmentation::create_segment_viz_points(
198+
visualization_msgs::msg::MarkerArray LaserSegmentation::create_segment_viz_points(
196199
std_msgs::msg::Header header,
197200
std::vector<slg::Segment2D> segment_list)
198201
{
@@ -273,7 +276,7 @@ visualization_msgs::msg::MarkerArray laserSegmentation::create_segment_viz_point
273276
return viz_array;
274277
}
275278

276-
std_msgs::msg::ColorRGBA laserSegmentation::get_parula_color(unsigned int index, unsigned int max)
279+
std_msgs::msg::ColorRGBA LaserSegmentation::get_parula_color(unsigned int index, unsigned int max)
277280
{
278281
std_msgs::msg::ColorRGBA color;
279282
int div = round(256 / max);
@@ -284,7 +287,7 @@ std_msgs::msg::ColorRGBA laserSegmentation::get_parula_color(unsigned int index,
284287
return color;
285288
}
286289

287-
std_msgs::msg::ColorRGBA laserSegmentation::get_palette_color(unsigned int index)
290+
std_msgs::msg::ColorRGBA LaserSegmentation::get_palette_color(unsigned int index)
288291
{
289292
std_msgs::msg::ColorRGBA color;
290293
switch (index % 8) {
@@ -302,5 +305,7 @@ std_msgs::msg::ColorRGBA laserSegmentation::get_palette_color(unsigned int index
302305
return color;
303306
}
304307

308+
} // namespace laser_segmentation
309+
305310
#include "rclcpp_components/register_node_macro.hpp"
306-
RCLCPP_COMPONENTS_REGISTER_NODE(laserSegmentation)
311+
RCLCPP_COMPONENTS_REGISTER_NODE(laser_segmentation::LaserSegmentation)

src/main.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -20,7 +20,7 @@
2020
int main(int argc, char ** argv)
2121
{
2222
rclcpp::init(argc, argv);
23-
auto node = std::make_shared<laserSegmentation>();
23+
auto node = std::make_shared<laser_segmentation::LaserSegmentation>();
2424
rclcpp::spin(node->get_node_base_interface());
2525
rclcpp::shutdown();
2626
return 0;

src/parameter_handler.cpp

+5
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,9 @@
2121

2222
#include "laser_segmentation/parameter_handler.hpp"
2323

24+
namespace laser_segmentation
25+
{
26+
2427
using nav2_util::declare_parameter_if_not_declared;
2528
using rcl_interfaces::msg::ParameterType;
2629

@@ -266,3 +269,5 @@ ParameterHandler::dynamicParametersCallback(std::vector<rclcpp::Parameter> param
266269
result.successful = true;
267270
return result;
268271
}
272+
273+
} // namespace laser_segmentation

src/segmentation/jump_distance.cpp

+5
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,9 @@
1414

1515
#include "laser_segmentation/segmentation/jump_distance.hpp"
1616

17+
namespace laser_segmentation
18+
{
19+
1720
void JumpDistanceSegmentation::initialize_segmentation(
1821
double jump_distance,
1922
double angle_resolution,
@@ -151,3 +154,5 @@ double JumpDistanceSegmentation::calculate_santos_threshold(
151154
return c0 + (c1 * minRange * tan(beta)) /
152155
(cos(angle_resolution_ / 2) - sin(angle_resolution_ / 2));
153156
}
157+
158+
} // namespace laser_segmentation

src/segmentation/jump_distance_merge.cpp

+5
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,9 @@
1414

1515
#include "laser_segmentation/segmentation/jump_distance_merge.hpp"
1616

17+
namespace laser_segmentation
18+
{
19+
1720
void JumpDistanceSegmentationMerge::initialize_segmentation(
1821
double jump_distance,
1922
double angle_resolution,
@@ -119,3 +122,5 @@ void JumpDistanceSegmentationMerge::perform_segmentation(
119122
segments.back().set_next_segment(first_segment.first_point());
120123
}
121124
}
125+
126+
} // namespace laser_segmentation

test/test_integration.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -32,7 +32,7 @@ TEST(LaserSegmentationTest, integration) {
3232
auto pub_thread = std::thread([&]() {rclcpp::spin(pub_node->get_node_base_interface());});
3333

3434
// Create and configure the laser_segmentation node
35-
auto seg_node = std::make_shared<laserSegmentation>();
35+
auto seg_node = std::make_shared<laser_segmentation::LaserSegmentation>();
3636
// Set some parameters
3737
nav2_util::declare_parameter_if_not_declared(
3838
seg_node, "min_points_segment", rclcpp::ParameterValue(1));

test/test_laser_segmentation.cpp

+7-7
Original file line numberDiff line numberDiff line change
@@ -16,36 +16,36 @@
1616
#include "rclcpp/rclcpp.hpp"
1717
#include "laser_segmentation/laser_segmentation.hpp"
1818

19-
class laserSegmentationFixture : public laserSegmentation
19+
class laserSegmentationFixture : public laser_segmentation::LaserSegmentation
2020
{
2121
public:
2222
laserSegmentationFixture()
23-
: laserSegmentation() {}
23+
: LaserSegmentation() {}
2424

2525
void scan_callback(const sensor_msgs::msg::LaserScan::SharedPtr msg)
2626
{
27-
laserSegmentation::scan_callback(msg);
27+
LaserSegmentation::scan_callback(msg);
2828
}
2929

3030
std::vector<slg::Segment2D> filter_segments(const std::vector<slg::Segment2D> & segments)
3131
{
32-
return laserSegmentation::filter_segments(segments);
32+
return LaserSegmentation::filter_segments(segments);
3333
}
3434

3535
visualization_msgs::msg::MarkerArray create_segment_viz_points(
3636
std_msgs::msg::Header header, std::vector<slg::Segment2D> segment_list)
3737
{
38-
return laserSegmentation::create_segment_viz_points(header, segment_list);
38+
return LaserSegmentation::create_segment_viz_points(header, segment_list);
3939
}
4040

4141
std_msgs::msg::ColorRGBA get_parula_color(unsigned int index, unsigned int max)
4242
{
43-
return laserSegmentation::get_parula_color(index, max);
43+
return LaserSegmentation::get_parula_color(index, max);
4444
}
4545

4646
std_msgs::msg::ColorRGBA get_palette_color(unsigned int index)
4747
{
48-
return laserSegmentation::get_palette_color(index);
48+
return LaserSegmentation::get_palette_color(index);
4949
}
5050
};
5151

test/test_segmentations.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,7 @@
1818
#include "laser_segmentation/segmentation/jump_distance.hpp"
1919
#include "laser_segmentation/segmentation/jump_distance_merge.hpp"
2020

21-
class JDistanceFixture : public JumpDistanceSegmentation
21+
class JDistanceFixture : public laser_segmentation::JumpDistanceSegmentation
2222
{
2323
public:
2424
JDistanceFixture()
@@ -70,7 +70,7 @@ class JDistanceFixture : public JumpDistanceSegmentation
7070
}
7171
};
7272

73-
class JDistanceMergeFixture : public JumpDistanceSegmentationMerge
73+
class JDistanceMergeFixture : public laser_segmentation::JumpDistanceSegmentationMerge
7474
{
7575
public:
7676
JDistanceMergeFixture()

0 commit comments

Comments
 (0)