Class LaserSegmentation

Inheritance Relationships

Base Type

  • public rclcpp_lifecycle::LifecycleNode

Class Documentation

class LaserSegmentation : public rclcpp_lifecycle::LifecycleNode

laser_segmentation::LaserSegmentation class is a ROS2 node that subscribes to a laser scan topic and publishes the segments found in the scan.

Public Functions

explicit LaserSegmentation(const rclcpp::NodeOptions &options = rclcpp::NodeOptions())

Construct a new laser Segmentation object.

Parameters:

options – Node options

~LaserSegmentation() = default

Destroy the laser Segmentation object.

CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override

Configure the node.

Parameters:

state – State of the node

Returns:

CallbackReturn

CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override

Activate the node.

Parameters:

state – State of the node

Returns:

CallbackReturn

CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override

Deactivate the node.

Parameters:

state – State of the node

Returns:

CallbackReturn

CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override

Cleanup the node.

Parameters:

state – State of the node

Returns:

CallbackReturn

CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override

Shutdown the node.

Parameters:

state – State of the node

Returns:

CallbackReturn

Protected Functions

void scan_callback(const sensor_msgs::msg::LaserScan::SharedPtr scan)

Callback executed when a new scan is received.

Parameters:

scan – The received scan

std::vector<slg::Segment2D> filter_segments(const std::vector<slg::Segment2D> &segments)

Filter the segments using the parameters.

Parameters:

segments – List of segments

Returns:

std::vector<slg::Segment2D> Filtered segments

visualization_msgs::msg::MarkerArray create_segment_viz_points(std_msgs::msg::Header header, std::vector<slg::Segment2D> segment_list)

Create the segment array message.

Parameters:
  • header – Header of the message

  • segment_list – List of segments

Returns:

slg_msgs::msg::SegmentArray The segment array message

std_msgs::msg::ColorRGBA get_parula_color(unsigned int index, unsigned int max)

Get the parula color object.

Parameters:
  • index – Index of the color

  • max – Maximum index

Returns:

std_msgs::msg::ColorRGBA The color

std_msgs::msg::ColorRGBA get_palette_color(unsigned int index)

Get the palette color object.

Parameters:

index – Index of the color

Returns:

std_msgs::msg::ColorRGBA The color

Protected Attributes

rclcpp_lifecycle::LifecyclePublisher<slg_msgs::msg::SegmentArray>::SharedPtr segment_pub_
rclcpp_lifecycle::LifecyclePublisher<visualization_msgs::msg::MarkerArray>::SharedPtr segment_viz_points_pub_
rclcpp::Subscription<sensor_msgs::msg::LaserScan>::SharedPtr scan_sub_
std::unique_ptr<ParameterHandler> param_handler_
Parameters *params_
std::shared_ptr<Segmentation> segmentation_