PointCloud Motion Capture
Pointcloud Motion Capture is a ROS 2 package designed to process point clouds for capturing object movements. It detects objects using color filters and infers data about their position, velocity, and acceleration. This package has been tested under [ROS] Humble and Ubuntu 22.04
Loading...
Searching...
No Matches
pointcloud_motion_capture::PointCloudProcessor Class Reference

#include <point_cloud_reader.hpp>

Inheritance diagram for pointcloud_motion_capture::PointCloudProcessor:
Collaboration diagram for pointcloud_motion_capture::PointCloudProcessor:

Public Member Functions

 PointCloudProcessor ()
 

Private Member Functions

void load_parameters ()
 Loads parameters from the ROS2 parameter server.
 
void pointCloudCallback (const sensor_msgs::msg::PointCloud2::SharedPtr msg)
 Callback function for processing incoming point cloud data.
 

Private Attributes

const int kRedThresholdDefault {40}
 Default value for the red color threshold.
 
const int kGreenThresholdDefault {30}
 Default value for the green color threshold.
 
const int kBlueThresholdDefault {30}
 Default value for the blue color threshold.
 
const float kUpdateRate {10.0}
 Default update rate (in Hz).
 
const std::string kPointCloudTopicRaw {"/camera/camera/depth/color/points"}
 ROS topic that receives the raw (unfiltered) point cloud.
 
const std::string kPointCloudTopicFiltered {"/point_cloud/filtered"}
 ROS topic that publishes the filtered point cloud.
 
rclcpp::Subscription< sensor_msgs::msg::PointCloud2 >::SharedPtr subscription_
 ROS2 subscription to receive PointCloud2 messages.
 
rclcpp::Publisher< sensor_msgs::msg::PointCloud2 >::SharedPtr publisher_
 ROS2 publisher to publish filtered PointCloud2 messages.
 
int red_threshold_ {}
 Threshold value for red color filtering.
 
int green_threshold_ {}
 Threshold value for green color filtering.
 
int blue_threshold_ {}
 Threshold value for blue color filtering.
 
std::string frame_id_ {"camera_link"}
 Frame ID used for the point cloud data.
 
std::string point_cloud_topic_raw_ {}
 ROS topic for receiving the raw point cloud data.
 
std::string point_cloud_topic_filtered_ {}
 ROS topic for publishing the filtered point cloud data.
 
float update_rate_ {}
 Update rate for processing the point cloud data.
 
sensor_msgs::msg::PointCloud2 filtered_msg_
 Holds the filtered PointCloud2 message.
 

Detailed Description

Definition at line 21 of file point_cloud_reader.hpp.

Constructor & Destructor Documentation

◆ PointCloudProcessor()

pointcloud_motion_capture::PointCloudProcessor::PointCloudProcessor ( )

Definition at line 7 of file point_cloud_reader.cpp.

8: Node("point_cloud_processor")
9{
11
12 subscription_ = this->create_subscription<sensor_msgs::msg::PointCloud2>(
14 std::bind(&PointCloudProcessor::pointCloudCallback, this, std::placeholders::_1));
15
16 publisher_ = this->create_publisher<sensor_msgs::msg::PointCloud2>(
18
19 RCLCPP_INFO(this->get_logger(), "PointCloudProcessor node initialized.");
20}
std::string point_cloud_topic_raw_
ROS topic for receiving the raw point cloud data.
std::string point_cloud_topic_filtered_
ROS topic for publishing the filtered point cloud data.
void load_parameters()
Loads parameters from the ROS2 parameter server.
float update_rate_
Update rate for processing the point cloud data.
rclcpp::Publisher< sensor_msgs::msg::PointCloud2 >::SharedPtr publisher_
ROS2 publisher to publish filtered PointCloud2 messages.
rclcpp::Subscription< sensor_msgs::msg::PointCloud2 >::SharedPtr subscription_
ROS2 subscription to receive PointCloud2 messages.
void pointCloudCallback(const sensor_msgs::msg::PointCloud2::SharedPtr msg)
Callback function for processing incoming point cloud data.

References load_parameters(), point_cloud_topic_filtered_, point_cloud_topic_raw_, pointCloudCallback(), publisher_, subscription_, and update_rate_.

Here is the call graph for this function:

Member Function Documentation

◆ load_parameters()

void pointcloud_motion_capture::PointCloudProcessor::load_parameters ( )
private

Loads parameters from the ROS2 parameter server.

This function retrieves parameters such as thresholds for color filtering and the topics names for point cloud data from the ROS2 parameter server.

Definition at line 22 of file point_cloud_reader.cpp.

23{
24 this->declare_parameter<int>("red_threshold", kRedThresholdDefault);
25 this->declare_parameter<int>("green_threshold", kGreenThresholdDefault);
26 this->declare_parameter<int>("blue_threshold", kBlueThresholdDefault);
27 this->declare_parameter<std::string>("point_cloud_topic_raw", kPointCloudTopicRaw);
28 this->declare_parameter<std::string>("point_cloud_topic_filtered", kPointCloudTopicFiltered);
29 this->declare_parameter<float>("update_rate", kUpdateRate);
30
31 this->get_parameter("red_threshold", red_threshold_);
32 this->get_parameter("green_threshold", green_threshold_);
33 this->get_parameter("blue_threshold", blue_threshold_);
34 this->get_parameter("point_cloud_topic_raw", point_cloud_topic_raw_);
35 this->get_parameter("point_cloud_topic_filtered", point_cloud_topic_filtered_);
36 this->get_parameter("update_rate", update_rate_);
37
38 RCLCPP_INFO(this->get_logger(), "Loading Parameters...");
39 RCLCPP_INFO(this->get_logger(), "Filter parameters:");
40 RCLCPP_INFO(this->get_logger(), " Red threshold: %d", red_threshold_);
41 RCLCPP_INFO(this->get_logger(), " Green threshold: %d", green_threshold_);
42 RCLCPP_INFO(this->get_logger(), " Blue threshold: %d", blue_threshold_);
43 RCLCPP_INFO(this->get_logger(), "Reading point cloud from: %s", point_cloud_topic_raw_.c_str());
44 RCLCPP_INFO(
45 this->get_logger(), "Publishing filtered point cloud on: %s",
47 RCLCPP_INFO(this->get_logger(), "Update Rate: %f Hz", update_rate_);
48}
const std::string kPointCloudTopicFiltered
ROS topic that publishes the filtered point cloud.
const int kBlueThresholdDefault
Default value for the blue color threshold.
const int kGreenThresholdDefault
Default value for the green color threshold.
const float kUpdateRate
Default update rate (in Hz).
int red_threshold_
Threshold value for red color filtering.
int green_threshold_
Threshold value for green color filtering.
int blue_threshold_
Threshold value for blue color filtering.
const int kRedThresholdDefault
Default value for the red color threshold.
const std::string kPointCloudTopicRaw
ROS topic that receives the raw (unfiltered) point cloud.

References blue_threshold_, green_threshold_, kBlueThresholdDefault, kGreenThresholdDefault, kPointCloudTopicFiltered, kPointCloudTopicRaw, kRedThresholdDefault, kUpdateRate, point_cloud_topic_filtered_, point_cloud_topic_raw_, red_threshold_, and update_rate_.

Referenced by PointCloudProcessor().

Here is the caller graph for this function:

◆ pointCloudCallback()

void pointcloud_motion_capture::PointCloudProcessor::pointCloudCallback ( const sensor_msgs::msg::PointCloud2::SharedPtr msg)
private

Callback function for processing incoming point cloud data.

Parameters
msgShared pointer to the incoming PointCloud2 message.

This function is triggered whenever a new point cloud message is received on the subscribed topic. It processes the raw point cloud and applies filtering based on the thresholds defined.

Definition at line 51 of file point_cloud_reader.cpp.

52{
53 pcl::PointCloud<pcl::PointXYZRGB>::Ptr pcl_cloud(new pcl::PointCloud<pcl::PointXYZRGB>());
54 pcl::fromROSMsg(*msg, *pcl_cloud);
55
56 pcl::PointCloud<pcl::PointXYZRGB>::Ptr filtered_cloud(new pcl::PointCloud<pcl::PointXYZRGB>());
57 for (const auto & point : *pcl_cloud) {
58 if (point.r > red_threshold_ && point.g < green_threshold_ && point.b < blue_threshold_) {
59 filtered_cloud->push_back(point);
60 }
61 }
62
63 pcl::toROSMsg(*filtered_cloud, filtered_msg_);
64 filtered_msg_.header.frame_id = frame_id_;
65 filtered_msg_.header.stamp = this->get_clock()->now();
66
67 publisher_->publish(filtered_msg_);
68}
std::string frame_id_
Frame ID used for the point cloud data.
sensor_msgs::msg::PointCloud2 filtered_msg_
Holds the filtered PointCloud2 message.

References blue_threshold_, filtered_msg_, frame_id_, green_threshold_, publisher_, and red_threshold_.

Referenced by PointCloudProcessor().

Here is the caller graph for this function:

Member Data Documentation

◆ blue_threshold_

int pointcloud_motion_capture::PointCloudProcessor::blue_threshold_ {}
private

Threshold value for blue color filtering.

This value is used to filter the point cloud based on the blue color component.

Definition at line 112 of file point_cloud_reader.hpp.

112{};

Referenced by load_parameters(), and pointCloudCallback().

◆ filtered_msg_

sensor_msgs::msg::PointCloud2 pointcloud_motion_capture::PointCloudProcessor::filtered_msg_
private

Holds the filtered PointCloud2 message.

This message contains the filtered point cloud data that is published after processing.

Definition at line 148 of file point_cloud_reader.hpp.

Referenced by pointCloudCallback().

◆ frame_id_

std::string pointcloud_motion_capture::PointCloudProcessor::frame_id_ {"camera_link"}
private

Frame ID used for the point cloud data.

The frame ID indicates the coordinate frame in which the point cloud data is represented. Default is "camera_link".

Definition at line 120 of file point_cloud_reader.hpp.

120{"camera_link"};

Referenced by pointCloudCallback().

◆ green_threshold_

int pointcloud_motion_capture::PointCloudProcessor::green_threshold_ {}
private

Threshold value for green color filtering.

This value is used to filter the point cloud based on the green color component.

Definition at line 105 of file point_cloud_reader.hpp.

105{};

Referenced by load_parameters(), and pointCloudCallback().

◆ kBlueThresholdDefault

const int pointcloud_motion_capture::PointCloudProcessor::kBlueThresholdDefault {30}
private

Default value for the blue color threshold.

Definition at line 40 of file point_cloud_reader.hpp.

40{30};

Referenced by load_parameters().

◆ kGreenThresholdDefault

const int pointcloud_motion_capture::PointCloudProcessor::kGreenThresholdDefault {30}
private

Default value for the green color threshold.

Definition at line 35 of file point_cloud_reader.hpp.

35{30};

Referenced by load_parameters().

◆ kPointCloudTopicFiltered

const std::string pointcloud_motion_capture::PointCloudProcessor::kPointCloudTopicFiltered {"/point_cloud/filtered"}
private

ROS topic that publishes the filtered point cloud.

Definition at line 55 of file point_cloud_reader.hpp.

55{"/point_cloud/filtered"};

Referenced by load_parameters().

◆ kPointCloudTopicRaw

const std::string pointcloud_motion_capture::PointCloudProcessor::kPointCloudTopicRaw {"/camera/camera/depth/color/points"}
private

ROS topic that receives the raw (unfiltered) point cloud.

Definition at line 50 of file point_cloud_reader.hpp.

50{"/camera/camera/depth/color/points"};

Referenced by load_parameters().

◆ kRedThresholdDefault

const int pointcloud_motion_capture::PointCloudProcessor::kRedThresholdDefault {40}
private

Default value for the red color threshold.

Definition at line 30 of file point_cloud_reader.hpp.

30{40};

Referenced by load_parameters().

◆ kUpdateRate

const float pointcloud_motion_capture::PointCloudProcessor::kUpdateRate {10.0}
private

Default update rate (in Hz).

Definition at line 45 of file point_cloud_reader.hpp.

45{10.0};

Referenced by load_parameters().

◆ point_cloud_topic_filtered_

std::string pointcloud_motion_capture::PointCloudProcessor::point_cloud_topic_filtered_ {}
private

ROS topic for publishing the filtered point cloud data.

This topic is where the filtered point cloud is published after processing.

Definition at line 134 of file point_cloud_reader.hpp.

134{};

Referenced by load_parameters(), and PointCloudProcessor().

◆ point_cloud_topic_raw_

std::string pointcloud_motion_capture::PointCloudProcessor::point_cloud_topic_raw_ {}
private

ROS topic for receiving the raw point cloud data.

This topic is where the raw (unfiltered) point cloud is subscribed from.

Definition at line 127 of file point_cloud_reader.hpp.

127{};

Referenced by load_parameters(), and PointCloudProcessor().

◆ publisher_

rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr pointcloud_motion_capture::PointCloudProcessor::publisher_
private

ROS2 publisher to publish filtered PointCloud2 messages.

This publisher is used to send the processed and filtered point cloud data (sensor_msgs::msg::PointCloud2) to a specific topic.

Definition at line 91 of file point_cloud_reader.hpp.

Referenced by pointCloudCallback(), and PointCloudProcessor().

◆ red_threshold_

int pointcloud_motion_capture::PointCloudProcessor::red_threshold_ {}
private

Threshold value for red color filtering.

This value is used to filter the point cloud based on the red color component.

Definition at line 98 of file point_cloud_reader.hpp.

98{};

Referenced by load_parameters(), and pointCloudCallback().

◆ subscription_

rclcpp::Subscription<sensor_msgs::msg::PointCloud2>::SharedPtr pointcloud_motion_capture::PointCloudProcessor::subscription_
private

ROS2 subscription to receive PointCloud2 messages.

This subscription listens to a topic that provides raw point cloud data (sensor_msgs::msg::PointCloud2) and triggers the callback function to process the incoming data.

Definition at line 83 of file point_cloud_reader.hpp.

Referenced by PointCloudProcessor().

◆ update_rate_

float pointcloud_motion_capture::PointCloudProcessor::update_rate_ {}
private

Update rate for processing the point cloud data.

This value controls how frequently the point cloud processing is updated, in Hz.

Definition at line 141 of file point_cloud_reader.hpp.

141{};

Referenced by load_parameters(), and PointCloudProcessor().


The documentation for this class was generated from the following files: