![]() |
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
|
#include <point_cloud_reader.hpp>
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. | |
Definition at line 21 of file point_cloud_reader.hpp.
pointcloud_motion_capture::PointCloudProcessor::PointCloudProcessor | ( | ) |
Definition at line 7 of file point_cloud_reader.cpp.
References load_parameters(), point_cloud_topic_filtered_, point_cloud_topic_raw_, pointCloudCallback(), publisher_, subscription_, and update_rate_.
|
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.
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().
|
private |
Callback function for processing incoming point cloud data.
msg | Shared 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.
References blue_threshold_, filtered_msg_, frame_id_, green_threshold_, publisher_, and red_threshold_.
Referenced by PointCloudProcessor().
|
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.
Referenced by load_parameters(), and pointCloudCallback().
|
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().
|
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.
Referenced by pointCloudCallback().
|
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.
Referenced by load_parameters(), and pointCloudCallback().
|
private |
Default value for the blue color threshold.
Definition at line 40 of file point_cloud_reader.hpp.
Referenced by load_parameters().
|
private |
Default value for the green color threshold.
Definition at line 35 of file point_cloud_reader.hpp.
Referenced by load_parameters().
|
private |
ROS topic that publishes the filtered point cloud.
Definition at line 55 of file point_cloud_reader.hpp.
Referenced by load_parameters().
|
private |
ROS topic that receives the raw (unfiltered) point cloud.
Definition at line 50 of file point_cloud_reader.hpp.
Referenced by load_parameters().
|
private |
Default value for the red color threshold.
Definition at line 30 of file point_cloud_reader.hpp.
Referenced by load_parameters().
|
private |
Default update rate (in Hz).
Definition at line 45 of file point_cloud_reader.hpp.
Referenced by load_parameters().
|
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.
Referenced by load_parameters(), and PointCloudProcessor().
|
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.
Referenced by load_parameters(), and PointCloudProcessor().
|
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().
|
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.
Referenced by load_parameters(), and pointCloudCallback().
|
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().
|
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.
Referenced by load_parameters(), and PointCloudProcessor().