14
14
15
15
#include " laser_segmentation/laser_segmentation.hpp"
16
16
17
- laserSegmentation::laserSegmentation (const rclcpp::NodeOptions & options)
17
+ namespace laser_segmentation
18
+ {
19
+
20
+ LaserSegmentation::LaserSegmentation (const rclcpp::NodeOptions & options)
18
21
: rclcpp_lifecycle::LifecycleNode(" laser_segmentation" , " " , options)
19
22
{
20
23
}
21
24
22
- CallbackReturn laserSegmentation ::on_configure (const rclcpp_lifecycle::State &)
25
+ CallbackReturn LaserSegmentation ::on_configure (const rclcpp_lifecycle::State &)
23
26
{
24
27
// Handles storage and dynamic configuration of parameters.
25
28
// Returns pointer to data current param settings.
@@ -48,14 +51,14 @@ CallbackReturn laserSegmentation::on_configure(const rclcpp_lifecycle::State &)
48
51
scan_sub_ = this ->create_subscription <sensor_msgs::msg::LaserScan>(
49
52
params_->scan_topic ,
50
53
default_qos,
51
- std::bind (&laserSegmentation ::scan_callback, this , std::placeholders::_1));
54
+ std::bind (&LaserSegmentation ::scan_callback, this , std::placeholders::_1));
52
55
53
56
RCLCPP_INFO (this ->get_logger (), " Configured laser segmentation node" );
54
57
55
58
return CallbackReturn::SUCCESS;
56
59
}
57
60
58
- CallbackReturn laserSegmentation ::on_activate (const rclcpp_lifecycle::State & state)
61
+ CallbackReturn LaserSegmentation ::on_activate (const rclcpp_lifecycle::State & state)
59
62
{
60
63
LifecycleNode::on_activate (state);
61
64
RCLCPP_INFO (this ->get_logger (), " Activating the node..." );
@@ -65,7 +68,7 @@ CallbackReturn laserSegmentation::on_activate(const rclcpp_lifecycle::State & st
65
68
return CallbackReturn::SUCCESS;
66
69
}
67
70
68
- CallbackReturn laserSegmentation ::on_deactivate (const rclcpp_lifecycle::State & state)
71
+ CallbackReturn LaserSegmentation ::on_deactivate (const rclcpp_lifecycle::State & state)
69
72
{
70
73
LifecycleNode::on_deactivate (state);
71
74
RCLCPP_INFO (this ->get_logger (), " Deactivating the node..." );
@@ -75,7 +78,7 @@ CallbackReturn laserSegmentation::on_deactivate(const rclcpp_lifecycle::State &
75
78
return CallbackReturn::SUCCESS;
76
79
}
77
80
78
- CallbackReturn laserSegmentation ::on_cleanup (const rclcpp_lifecycle::State & /* state*/ )
81
+ CallbackReturn LaserSegmentation ::on_cleanup (const rclcpp_lifecycle::State & /* state*/ )
79
82
{
80
83
RCLCPP_INFO (this ->get_logger (), " Cleaning the node..." );
81
84
@@ -87,7 +90,7 @@ CallbackReturn laserSegmentation::on_cleanup(const rclcpp_lifecycle::State & /*s
87
90
return CallbackReturn::SUCCESS;
88
91
}
89
92
90
- CallbackReturn laserSegmentation ::on_shutdown (const rclcpp_lifecycle::State & state)
93
+ CallbackReturn LaserSegmentation ::on_shutdown (const rclcpp_lifecycle::State & state)
91
94
{
92
95
RCLCPP_INFO (this ->get_logger (), " Shutdown the node from state %s." , state.label ().c_str ());
93
96
@@ -98,7 +101,7 @@ CallbackReturn laserSegmentation::on_shutdown(const rclcpp_lifecycle::State & st
98
101
return CallbackReturn::SUCCESS;
99
102
}
100
103
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)
102
105
{
103
106
std::lock_guard<std::mutex> param_lock (param_handler_->getMutex ());
104
107
@@ -156,7 +159,7 @@ void laserSegmentation::scan_callback(const sensor_msgs::msg::LaserScan::SharedP
156
159
create_segment_viz_points (scan_msg->header , segment_filtered_list));
157
160
}
158
161
159
- std::vector<slg::Segment2D> laserSegmentation ::filter_segments (
162
+ std::vector<slg::Segment2D> LaserSegmentation ::filter_segments (
160
163
const std::vector<slg::Segment2D> & segments)
161
164
{
162
165
std::vector<slg::Segment2D> filtered_segments;
@@ -192,7 +195,7 @@ std::vector<slg::Segment2D> laserSegmentation::filter_segments(
192
195
return filtered_segments;
193
196
}
194
197
195
- visualization_msgs::msg::MarkerArray laserSegmentation ::create_segment_viz_points (
198
+ visualization_msgs::msg::MarkerArray LaserSegmentation ::create_segment_viz_points (
196
199
std_msgs::msg::Header header,
197
200
std::vector<slg::Segment2D> segment_list)
198
201
{
@@ -273,7 +276,7 @@ visualization_msgs::msg::MarkerArray laserSegmentation::create_segment_viz_point
273
276
return viz_array;
274
277
}
275
278
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)
277
280
{
278
281
std_msgs::msg::ColorRGBA color;
279
282
int div = round (256 / max);
@@ -284,7 +287,7 @@ std_msgs::msg::ColorRGBA laserSegmentation::get_parula_color(unsigned int index,
284
287
return color;
285
288
}
286
289
287
- std_msgs::msg::ColorRGBA laserSegmentation ::get_palette_color (unsigned int index)
290
+ std_msgs::msg::ColorRGBA LaserSegmentation ::get_palette_color (unsigned int index)
288
291
{
289
292
std_msgs::msg::ColorRGBA color;
290
293
switch (index % 8 ) {
@@ -302,5 +305,7 @@ std_msgs::msg::ColorRGBA laserSegmentation::get_palette_color(unsigned int index
302
305
return color;
303
306
}
304
307
308
+ } // namespace laser_segmentation
309
+
305
310
#include " rclcpp_components/register_node_macro.hpp"
306
- RCLCPP_COMPONENTS_REGISTER_NODE (laserSegmentation )
311
+ RCLCPP_COMPONENTS_REGISTER_NODE (laser_segmentation::LaserSegmentation )
0 commit comments