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
point_cloud_reader.hpp
Go to the documentation of this file.
1// Copyright 2024 João Vitor Silva Mendes
2
3#ifndef POINT_CLOUD_READER_HPP_
4#define POINT_CLOUD_READER_HPP_
5
6#include <pcl_conversions/pcl_conversions.h>
7#include <pcl/point_types.h>
8#include <pcl/point_cloud.h>
9
10#include <memory>
11#include <string>
12#include <fstream>
13
14#include <rclcpp/rclcpp.hpp>
15#include <sensor_msgs/msg/point_cloud2.hpp>
16#include <ament_index_cpp/get_package_share_directory.hpp>
17
18
20{
21class PointCloudProcessor : public rclcpp::Node
22{
23public:
25
26private:
30 const int kRedThresholdDefault {40};
31
35 const int kGreenThresholdDefault {30};
36
40 const int kBlueThresholdDefault {30};
41
45 const float kUpdateRate {10.0};
46
50 const std::string kPointCloudTopicRaw {"/camera/camera/depth/color/points"};
51
55 const std::string kPointCloudTopicFiltered {"/point_cloud/filtered"};
56
63 void load_parameters();
64
74 void pointCloudCallback(const sensor_msgs::msg::PointCloud2::SharedPtr msg);
75
83 rclcpp::Subscription<sensor_msgs::msg::PointCloud2>::SharedPtr subscription_;
84
91 rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr publisher_;
92
99
106
113
120 std::string frame_id_ {"camera_link"};
121
128
135
141 float update_rate_ {};
142
148 sensor_msgs::msg::PointCloud2 filtered_msg_;
149};
150
151} // namespace pointcloud_motion_capture
152
153#endif // POINT_CLOUD_READER_HPP_
const std::string kPointCloudTopicFiltered
ROS topic that publishes the filtered point cloud.
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.
const int kBlueThresholdDefault
Default value for the blue color threshold.
const int kGreenThresholdDefault
Default value for the green color threshold.
void load_parameters()
Loads parameters from the ROS2 parameter server.
float update_rate_
Update rate for processing the point cloud data.
const float kUpdateRate
Default update rate (in Hz).
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.
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.
std::string frame_id_
Frame ID used for the point cloud data.
int blue_threshold_
Threshold value for blue color filtering.
const int kRedThresholdDefault
Default value for the red color threshold.
sensor_msgs::msg::PointCloud2 filtered_msg_
Holds the filtered PointCloud2 message.
const std::string kPointCloudTopicRaw
ROS topic that receives the raw (unfiltered) point cloud.