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::MotionCapture Class Reference

#include <motion_capture.hpp>

Inheritance diagram for pointcloud_motion_capture::MotionCapture:
Collaboration diagram for pointcloud_motion_capture::MotionCapture:

Public Types

enum  CentroidIndex { kCentroidX = 0 , kCentroidY = 1 , kCentroidZ = 2 }
 Enumeration representing indices for the centroid coordinates. More...
 
enum  VectorIndex { kVectorX = 0 , kVectorY = 1 , kVectorZ = 2 }
 Enumeration representing indices for the velocity vector. More...
 

Public Member Functions

 MotionCapture ()
 Constructor for the MotionCapture class.
 

Public Attributes

std::string kDefaultPointCloudTopicFiltered {"/point_cloud/filtered"}
 Default topic name for subscribing to the filtered point cloud data.
 
std::string kDefaultPositionPublishTopic {"/object_position"}
 Default topic name for publishing the calculated object position.
 
std::string kDefaultVelocityPublishTopic {"/object_velocity"}
 Default topic name for publishing the calculated object velocity.
 
std::string kDefaultAccelerationPublishTopic {"/object_acceleration"}
 Default topic name for publishing the calculated object acceleration.
 
int kDefaultPositionSamples {5}
 Default number of position samples used for calculations.
 
int kDefaultVelocitySamples {5}
 Default number of velocity samples used for calculations.
 
double kDefaultPublishRate {10.0}
 Default publish rate in Hz for publishing position, velocity, and acceleration.
 
int kDefaultQueueSize {10}
 Default queue size for ROS publishers and subscriptions.
 
double kMillisecondsPerSecond {1000.0}
 Conversion factor from seconds to milliseconds.
 

Private Member Functions

void pointCloudCallback (const sensor_msgs::msg::PointCloud2::SharedPtr msg)
 Callback function for processing incoming PointCloud2 messages.
 
void updatePositionSamples (const Eigen::Vector4f &centroid)
 Updates the position samples queue with a new centroid value.
 
Eigen::Vector4f getFilteredPosition ()
 Retrieves the filtered position of the object.
 
void updateVelocitySamples (const Eigen::Vector3f &velocity)
 Updates the velocity samples queue with a new velocity value.
 
Eigen::Vector3f getFilteredVelocity ()
 Retrieves the filtered velocity of the object.
 
void publishData ()
 Publishes the calculated position, velocity, and acceleration.
 
void publishPosition (const Eigen::Vector4f &centroid)
 Publishes the object's position to a ROS topic.
 
Eigen::Vector3f publishVelocity (const Eigen::Vector4f &current_position)
 Publishes the object's velocity to a ROS topic.
 
void publishAcceleration (const Eigen::Vector3f &current_velocity)
 Publishes the object's acceleration to a ROS topic.
 
void loadParameters ()
 Loads parameters from the ROS2 parameter server.
 

Private Attributes

rclcpp::Subscription< sensor_msgs::msg::PointCloud2 >::SharedPtr subscription_
 ROS2 subscription to receive PointCloud2 messages.
 
rclcpp::Publisher< geometry_msgs::msg::Point >::SharedPtr position_publisher_
 ROS2 publisher to send the calculated object position.
 
rclcpp::Publisher< geometry_msgs::msg::Vector3 >::SharedPtr velocity_publisher_
 ROS2 publisher to send the calculated object velocity.
 
rclcpp::Publisher< geometry_msgs::msg::Vector3 >::SharedPtr acceleration_publisher_
 ROS2 publisher to send the calculated object acceleration.
 
std::queue< Eigen::Vector4f > position_queue_
 Queue to store recent position samples for calculating position.
 
std::queue< Eigen::Vector3f > velocity_queue_
 Queue to store recent velocity samples for calculating velocity.
 
Eigen::Vector4f previous_position_
 The previous position of the object in 3D space.
 
Eigen::Vector3f previous_velocity_
 The previous velocity of the object in 3D space.
 
rclcpp::Time previous_time_
 The timestamp of the previous position sample.
 
rclcpp::Time previous_velocity_time_
 The timestamp of the previous velocity sample.
 
int position_samples_
 Number of position samples used for calculations.
 
int velocity_samples_
 Number of velocity samples used for calculations.
 
int queue_size_
 Queue size for message publishers and subscriptions.
 
double publish_rate_
 Publish rate for sending position, velocity, and acceleration data.
 
rclcpp::TimerBase::SharedPtr timer_
 Timer used for scheduling the publication of data.
 
std::string point_cloud_topic_filtered_
 Topic name for subscribing to filtered point cloud data.
 
std::string position_publish_topic_
 Topic name for publishing the calculated position of an object.
 
std::string velocity_publish_topic_
 Topic name for publishing the calculated velocity of an object.
 
std::string acceleration_publish_topic_
 Topic name for publishing the calculated acceleration of an object.
 

Detailed Description

Definition at line 22 of file motion_capture.hpp.

Member Enumeration Documentation

◆ CentroidIndex

Enumeration representing indices for the centroid coordinates.

This enum defines indices for accessing the X, Y, and Z coordinates of the centroid in the Eigen::Vector4f. These indices help in improving the readability when accessing specific dimensions of the centroid vector.

Enumerator
kCentroidX 

Index for the X-coordinate of the centroid.

kCentroidY 

Index for the Y-coordinate of the centroid.

kCentroidZ 

Index for the Z-coordinate of the centroid.

Definition at line 32 of file motion_capture.hpp.

33 {
34 kCentroidX = 0,
35 kCentroidY = 1,
36 kCentroidZ = 2
37 };
@ kCentroidY
Index for the Y-coordinate of the centroid.
@ kCentroidX
Index for the X-coordinate of the centroid.
@ kCentroidZ
Index for the Z-coordinate of the centroid.

◆ VectorIndex

Enumeration representing indices for the velocity vector.

This enum defines indices for accessing the X, Y, and Z components of a velocity vector in the Eigen::Vector3f. These indices help improve readability when accessing specific dimensions of the velocity vector.

Enumerator
kVectorX 

Index for the X-component of the velocity vector.

kVectorY 

Index for the Y-component of the velocity vector.

kVectorZ 

Index for the Z-component of the velocity vector.

Definition at line 46 of file motion_capture.hpp.

47 {
48 kVectorX = 0,
49 kVectorY = 1,
50 kVectorZ = 2
51 };
@ kVectorZ
Index for the Z-component of the velocity vector.
@ kVectorY
Index for the Y-component of the velocity vector.
@ kVectorX
Index for the X-component of the velocity vector.

Constructor & Destructor Documentation

◆ MotionCapture()

pointcloud_motion_capture::MotionCapture::MotionCapture ( )

Constructor for the MotionCapture class.

This constructor initializes the MotionCapture node, setting up the necessary ROS2 publishers, subscriptions, and timers. It also initializes default values for position, velocity, and other parameters.

Definition at line 7 of file motion_capture.cpp.

8: Node("motion_capture"),
9 previous_position_(Eigen::Vector4f::Zero()),
10 previous_velocity_(Eigen::Vector3f::Zero()),
11 previous_time_(this->now()), previous_velocity_time_(this->now())
12{
14
15 subscription_ = this->create_subscription<sensor_msgs::msg::PointCloud2>(
17 std::bind(&MotionCapture::pointCloudCallback, this, std::placeholders::_1));
18
19 position_publisher_ = this->create_publisher<geometry_msgs::msg::Point>(
21
22 velocity_publisher_ = this->create_publisher<geometry_msgs::msg::Vector3>(
24
25 acceleration_publisher_ = this->create_publisher<geometry_msgs::msg::Vector3>(
27
28 timer_ = this->create_wall_timer(
29 std::chrono::milliseconds(static_cast<int>(kMillisecondsPerSecond / publish_rate_)),
30 std::bind(&MotionCapture::publishData, this));
31
32 RCLCPP_INFO(this->get_logger(), "MotionCapture node initialized.");
33}
rclcpp::Publisher< geometry_msgs::msg::Vector3 >::SharedPtr acceleration_publisher_
ROS2 publisher to send the calculated object acceleration.
void publishData()
Publishes the calculated position, velocity, and acceleration.
Eigen::Vector4f previous_position_
The previous position of the object in 3D space.
std::string acceleration_publish_topic_
Topic name for publishing the calculated acceleration of an object.
void loadParameters()
Loads parameters from the ROS2 parameter server.
rclcpp::Time previous_time_
The timestamp of the previous position sample.
rclcpp::Publisher< geometry_msgs::msg::Vector3 >::SharedPtr velocity_publisher_
ROS2 publisher to send the calculated object velocity.
std::string point_cloud_topic_filtered_
Topic name for subscribing to filtered point cloud data.
double kMillisecondsPerSecond
Conversion factor from seconds to milliseconds.
int queue_size_
Queue size for message publishers and subscriptions.
rclcpp::TimerBase::SharedPtr timer_
Timer used for scheduling the publication of data.
Eigen::Vector3f previous_velocity_
The previous velocity of the object in 3D space.
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 PointCloud2 messages.
std::string velocity_publish_topic_
Topic name for publishing the calculated velocity of an object.
rclcpp::Publisher< geometry_msgs::msg::Point >::SharedPtr position_publisher_
ROS2 publisher to send the calculated object position.
rclcpp::Time previous_velocity_time_
The timestamp of the previous velocity sample.
std::string position_publish_topic_
Topic name for publishing the calculated position of an object.
double publish_rate_
Publish rate for sending position, velocity, and acceleration data.

References acceleration_publish_topic_, acceleration_publisher_, kMillisecondsPerSecond, loadParameters(), point_cloud_topic_filtered_, pointCloudCallback(), position_publish_topic_, position_publisher_, publish_rate_, publishData(), queue_size_, subscription_, timer_, velocity_publish_topic_, and velocity_publisher_.

Here is the call graph for this function:

Member Function Documentation

◆ getFilteredPosition()

Eigen::Vector4f pointcloud_motion_capture::MotionCapture::getFilteredPosition ( )
private

Retrieves the filtered position of the object.

This function calculates and returns the filtered position of the object based on the stored position samples. The filtering is typically done by averaging or applying a smoothing algorithm to the samples in the queue.

Returns
The filtered position as Eigen::Vector4f.

Definition at line 78 of file motion_capture.cpp.

79{
80 Eigen::Vector4f sum = Eigen::Vector4f::Zero();
81 std::queue<Eigen::Vector4f> temp_queue = position_queue_;
82 while (!temp_queue.empty()) {
83 sum += temp_queue.front();
84 temp_queue.pop();
85 }
86 return sum / position_queue_.size();
87}
std::queue< Eigen::Vector4f > position_queue_
Queue to store recent position samples for calculating position.

References position_queue_.

Referenced by publishData().

Here is the caller graph for this function:

◆ getFilteredVelocity()

Eigen::Vector3f pointcloud_motion_capture::MotionCapture::getFilteredVelocity ( )
private

Retrieves the filtered velocity of the object.

This function calculates and returns the filtered velocity of the object based on the stored velocity samples. The filtering is typically done by averaging or applying a smoothing algorithm to the samples in the queue.

Returns
The filtered velocity as Eigen::Vector3f.

Definition at line 97 of file motion_capture.cpp.

98{
99 Eigen::Vector3f sum = Eigen::Vector3f::Zero();
100 std::queue<Eigen::Vector3f> temp_queue = velocity_queue_;
101 while (!temp_queue.empty()) {
102 sum += temp_queue.front();
103 temp_queue.pop();
104 }
105 return sum / velocity_queue_.size();
106}
std::queue< Eigen::Vector3f > velocity_queue_
Queue to store recent velocity samples for calculating velocity.

References velocity_queue_.

Referenced by publishData().

Here is the caller graph for this function:

◆ loadParameters()

void pointcloud_motion_capture::MotionCapture::loadParameters ( )
private

Loads parameters from the ROS2 parameter server.

This function retrieves the necessary parameters from the ROS2 parameter server to configure the node. Parameters include topics for publishing and subscribing, the number of samples for position and velocity calculations, the queue size, and the publish rate.

Definition at line 35 of file motion_capture.cpp.

36{
37 this->declare_parameter<std::string>(
38 "point_cloud_topic_filtered",
40 this->declare_parameter<std::string>("position_publish_topic", kDefaultPositionPublishTopic);
41 this->declare_parameter<std::string>("velocity_publish_topic", kDefaultVelocityPublishTopic);
42 this->declare_parameter<std::string>(
43 "acceleration_publish_topic",
45 this->declare_parameter<int>("position_samples", kDefaultPositionSamples);
46 this->declare_parameter<int>("velocity_samples", kDefaultVelocitySamples);
47 this->declare_parameter<double>("publish_rate", kDefaultPublishRate);
48 this->declare_parameter<int>("queue_size", kDefaultQueueSize);
49 point_cloud_topic_filtered_ = this->get_parameter("point_cloud_topic_filtered").as_string();
50 position_publish_topic_ = this->get_parameter("position_publish_topic").as_string();
51 velocity_publish_topic_ = this->get_parameter("velocity_publish_topic").as_string();
52 acceleration_publish_topic_ = this->get_parameter("acceleration_publish_topic").as_string();
53 position_samples_ = this->get_parameter("position_samples").as_int();
54 velocity_samples_ = this->get_parameter("velocity_samples").as_int();
55 publish_rate_ = this->get_parameter("publish_rate").as_double();
56 queue_size_ = this->get_parameter("queue_size").as_int();
57}
double kDefaultPublishRate
Default publish rate in Hz for publishing position, velocity, and acceleration.
int kDefaultQueueSize
Default queue size for ROS publishers and subscriptions.
std::string kDefaultPointCloudTopicFiltered
Default topic name for subscribing to the filtered point cloud data.
int kDefaultPositionSamples
Default number of position samples used for calculations.
std::string kDefaultAccelerationPublishTopic
Default topic name for publishing the calculated object acceleration.
int kDefaultVelocitySamples
Default number of velocity samples used for calculations.
int velocity_samples_
Number of velocity samples used for calculations.
std::string kDefaultPositionPublishTopic
Default topic name for publishing the calculated object position.
int position_samples_
Number of position samples used for calculations.
std::string kDefaultVelocityPublishTopic
Default topic name for publishing the calculated object velocity.

References acceleration_publish_topic_, kDefaultAccelerationPublishTopic, kDefaultPointCloudTopicFiltered, kDefaultPositionPublishTopic, kDefaultPositionSamples, kDefaultPublishRate, kDefaultQueueSize, kDefaultVelocityPublishTopic, kDefaultVelocitySamples, point_cloud_topic_filtered_, position_publish_topic_, position_samples_, publish_rate_, queue_size_, velocity_publish_topic_, and velocity_samples_.

Referenced by MotionCapture().

Here is the caller graph for this function:

◆ pointCloudCallback()

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

Callback function for processing incoming PointCloud2 messages.

This function is triggered whenever a new PointCloud2 message is received on the subscribed topic. It processes the point cloud data to extract the centroid of the object and updates the position samples for further calculations.

Parameters
msgShared pointer to the received sensor_msgs::msg::PointCloud2 message.

Definition at line 59 of file motion_capture.cpp.

60{
61 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZRGB>);
62 pcl::fromROSMsg(*msg, *cloud);
63
64 Eigen::Vector4f centroid;
65 pcl::compute3DCentroid(*cloud, centroid);
66
67 updatePositionSamples(centroid);
68}
void updatePositionSamples(const Eigen::Vector4f &centroid)
Updates the position samples queue with a new centroid value.

References updatePositionSamples().

Referenced by MotionCapture().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ publishAcceleration()

void pointcloud_motion_capture::MotionCapture::publishAcceleration ( const Eigen::Vector3f & current_velocity)
private

Publishes the object's acceleration to a ROS topic.

This function calculates the object's acceleration based on the current velocity and the previous velocity. It then publishes the calculated acceleration as a geometry_msgs::msg::Vector3 message.

Parameters
current_velocityThe current velocity of the object in 3D space, represented as Eigen::Vector3f.

Definition at line 162 of file motion_capture.cpp.

163{
164 rclcpp::Time current_time = this->now();
165 double time_difference = (current_time - previous_velocity_time_).seconds();
166 Eigen::Vector3f acceleration = Eigen::Vector3f::Zero();
167
168 if (time_difference > 0) {
169 acceleration[kVectorX] = (current_velocity[kVectorX] - previous_velocity_[kVectorX]) /
170 time_difference;
171 acceleration[kVectorY] = (current_velocity[kVectorY] - previous_velocity_[kVectorY]) /
172 time_difference;
173 acceleration[kVectorZ] = (current_velocity[kVectorZ] - previous_velocity_[kVectorZ]) /
174 time_difference;
175
176 geometry_msgs::msg::Vector3 acceleration_msg;
177 acceleration_msg.x = acceleration[kVectorX];
178 acceleration_msg.y = acceleration[kVectorY];
179 acceleration_msg.z = acceleration[kVectorZ];
180
181 acceleration_publisher_->publish(acceleration_msg);
182 }
183
184 previous_velocity_ = current_velocity;
185 previous_velocity_time_ = current_time;
186}

References acceleration_publisher_, kVectorX, kVectorY, kVectorZ, previous_velocity_, and previous_velocity_time_.

Referenced by publishData().

Here is the caller graph for this function:

◆ publishData()

void pointcloud_motion_capture::MotionCapture::publishData ( )
private

Publishes the calculated position, velocity, and acceleration.

This function is triggered by a ROS2 timer and publishes the calculated position, velocity, and acceleration data at regular intervals. The data is published to the respective ROS topics as geometry_msgs messages.

Definition at line 108 of file motion_capture.cpp.

109{
110 if (!position_queue_.empty()) {
111 Eigen::Vector4f filtered_position = getFilteredPosition();
112 publishPosition(filtered_position);
113
114 Eigen::Vector3f current_velocity = publishVelocity(filtered_position);
115 updateVelocitySamples(current_velocity);
116
117 if (!velocity_queue_.empty()) {
118 Eigen::Vector3f filtered_velocity = getFilteredVelocity();
119 publishAcceleration(filtered_velocity);
120 }
121
122 previous_position_ = filtered_position;
123 previous_time_ = this->now();
124 }
125}
Eigen::Vector4f getFilteredPosition()
Retrieves the filtered position of the object.
Eigen::Vector3f publishVelocity(const Eigen::Vector4f &current_position)
Publishes the object's velocity to a ROS topic.
Eigen::Vector3f getFilteredVelocity()
Retrieves the filtered velocity of the object.
void publishPosition(const Eigen::Vector4f &centroid)
Publishes the object's position to a ROS topic.
void updateVelocitySamples(const Eigen::Vector3f &velocity)
Updates the velocity samples queue with a new velocity value.
void publishAcceleration(const Eigen::Vector3f &current_velocity)
Publishes the object's acceleration to a ROS topic.

References getFilteredPosition(), getFilteredVelocity(), position_queue_, previous_position_, previous_time_, publishAcceleration(), publishPosition(), publishVelocity(), updateVelocitySamples(), and velocity_queue_.

Referenced by MotionCapture().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ publishPosition()

void pointcloud_motion_capture::MotionCapture::publishPosition ( const Eigen::Vector4f & centroid)
private

Publishes the object's position to a ROS topic.

This function takes the object's centroid as input and publishes its position to the specified ROS topic as a geometry_msgs::msg::Point message.

Parameters
centroidThe centroid of the object in 3D space, represented as Eigen::Vector4f.

Definition at line 127 of file motion_capture.cpp.

128{
129 geometry_msgs::msg::Point position_msg;
130 position_msg.x = centroid[kCentroidX];
131 position_msg.y = centroid[kCentroidY];
132 position_msg.z = centroid[kCentroidZ];
133
134 position_publisher_->publish(position_msg);
135}

References kCentroidX, kCentroidY, kCentroidZ, and position_publisher_.

Referenced by publishData().

Here is the caller graph for this function:

◆ publishVelocity()

Eigen::Vector3f pointcloud_motion_capture::MotionCapture::publishVelocity ( const Eigen::Vector4f & current_position)
private

Publishes the object's velocity to a ROS topic.

This function calculates the object's velocity based on the current position and the previous position. It then publishes the calculated velocity as a geometry_msgs::msg::Vector3 message.

Parameters
current_positionThe current position of the object in 3D space, represented as Eigen::Vector4f.
Returns
The calculated velocity as Eigen::Vector3f.

Definition at line 137 of file motion_capture.cpp.

138{
139 rclcpp::Time current_time = this->now();
140 double time_difference = (current_time - previous_time_).seconds();
141 Eigen::Vector3f velocity = Eigen::Vector3f::Zero();
142
143 if (time_difference > 0) {
144 velocity[kCentroidX] = (current_position[kCentroidX] - previous_position_[kCentroidX]) /
145 time_difference;
146 velocity[kCentroidY] = (current_position[kCentroidY] - previous_position_[kCentroidY]) /
147 time_difference;
148 velocity[kCentroidZ] = (current_position[kCentroidZ] - previous_position_[kCentroidZ]) /
149 time_difference;
150
151 geometry_msgs::msg::Vector3 velocity_msg;
152 velocity_msg.x = velocity[kCentroidX];
153 velocity_msg.y = velocity[kCentroidY];
154 velocity_msg.z = velocity[kCentroidZ];
155
156 velocity_publisher_->publish(velocity_msg);
157 }
158
159 return velocity;
160}

References kCentroidX, kCentroidY, kCentroidZ, previous_position_, previous_time_, and velocity_publisher_.

Referenced by publishData().

Here is the caller graph for this function:

◆ updatePositionSamples()

void pointcloud_motion_capture::MotionCapture::updatePositionSamples ( const Eigen::Vector4f & centroid)
private

Updates the position samples queue with a new centroid value.

This function adds the given centroid value to the position samples queue. The queue is used to store recent position data for calculating the filtered position of the object.

Parameters
centroidThe centroid of the object in 3D space, represented as Eigen::Vector4f.

Definition at line 70 of file motion_capture.cpp.

71{
72 if (static_cast<int>(position_queue_.size()) >= position_samples_) {
73 position_queue_.pop();
74 }
75 position_queue_.push(centroid);
76}

References position_queue_, and position_samples_.

Referenced by pointCloudCallback().

Here is the caller graph for this function:

◆ updateVelocitySamples()

void pointcloud_motion_capture::MotionCapture::updateVelocitySamples ( const Eigen::Vector3f & velocity)
private

Updates the velocity samples queue with a new velocity value.

This function adds the given velocity value to the velocity samples queue. The queue is used to store recent velocity data for calculating the filtered velocity of the object.

Parameters
velocityThe velocity of the object in 3D space, represented as Eigen::Vector3f.

Definition at line 89 of file motion_capture.cpp.

90{
91 if (static_cast<int>(velocity_queue_.size()) >= velocity_samples_) {
92 velocity_queue_.pop();
93 }
94 velocity_queue_.push(velocity);
95}

References velocity_queue_, and velocity_samples_.

Referenced by publishData().

Here is the caller graph for this function:

Member Data Documentation

◆ acceleration_publish_topic_

std::string pointcloud_motion_capture::MotionCapture::acceleration_publish_topic_
private

Topic name for publishing the calculated acceleration of an object.

This string value holds the name of the topic that the node publishes calculated acceleration data to, as geometry_msgs::msg::Vector3 messages.

Definition at line 410 of file motion_capture.hpp.

Referenced by loadParameters(), and MotionCapture().

◆ acceleration_publisher_

rclcpp::Publisher<geometry_msgs::msg::Vector3>::SharedPtr pointcloud_motion_capture::MotionCapture::acceleration_publisher_
private

ROS2 publisher to send the calculated object acceleration.

This publisher sends geometry_msgs::msg::Vector3 messages, representing the estimated acceleration of an object. The acceleration is computed as the change in velocity over time, based on sequential velocity samples.

Definition at line 282 of file motion_capture.hpp.

Referenced by MotionCapture(), and publishAcceleration().

◆ kDefaultAccelerationPublishTopic

std::string pointcloud_motion_capture::MotionCapture::kDefaultAccelerationPublishTopic {"/object_acceleration"}

Default topic name for publishing the calculated object acceleration.

This string stores the default ROS topic name where the calculated object acceleration (as geometry_msgs::msg::Vector3) is published.

Definition at line 84 of file motion_capture.hpp.

84{"/object_acceleration"};

Referenced by loadParameters().

◆ kDefaultPointCloudTopicFiltered

std::string pointcloud_motion_capture::MotionCapture::kDefaultPointCloudTopicFiltered {"/point_cloud/filtered"}

Default topic name for subscribing to the filtered point cloud data.

This string stores the default ROS topic name for the filtered point cloud data, which the node subscribes to in order to process the point cloud and extract relevant object information.

Definition at line 60 of file motion_capture.hpp.

60{"/point_cloud/filtered"};

Referenced by loadParameters().

◆ kDefaultPositionPublishTopic

std::string pointcloud_motion_capture::MotionCapture::kDefaultPositionPublishTopic {"/object_position"}

Default topic name for publishing the calculated object position.

This string stores the default ROS topic name where the calculated object position (as geometry_msgs::msg::Point) is published.

Definition at line 68 of file motion_capture.hpp.

68{"/object_position"};

Referenced by loadParameters().

◆ kDefaultPositionSamples

int pointcloud_motion_capture::MotionCapture::kDefaultPositionSamples {5}

Default number of position samples used for calculations.

This integer value defines the default number of recent position samples stored in the position queue and used for calculating the filtered position of the object.

Definition at line 93 of file motion_capture.hpp.

93{5};

Referenced by loadParameters().

◆ kDefaultPublishRate

double pointcloud_motion_capture::MotionCapture::kDefaultPublishRate {10.0}

Default publish rate in Hz for publishing position, velocity, and acceleration.

This double value defines the default rate, in Hz, at which the position, velocity, and acceleration data are published to their respective ROS topics.

Definition at line 110 of file motion_capture.hpp.

110{10.0};

Referenced by loadParameters().

◆ kDefaultQueueSize

int pointcloud_motion_capture::MotionCapture::kDefaultQueueSize {10}

Default queue size for ROS publishers and subscriptions.

This integer value defines the default queue size for both publishers and subscriptions, controlling how many messages are stored before being processed or discarded.

Definition at line 119 of file motion_capture.hpp.

119{10};

Referenced by loadParameters().

◆ kDefaultVelocityPublishTopic

std::string pointcloud_motion_capture::MotionCapture::kDefaultVelocityPublishTopic {"/object_velocity"}

Default topic name for publishing the calculated object velocity.

This string stores the default ROS topic name where the calculated object velocity (as geometry_msgs::msg::Vector3) is published.

Definition at line 76 of file motion_capture.hpp.

76{"/object_velocity"};

Referenced by loadParameters().

◆ kDefaultVelocitySamples

int pointcloud_motion_capture::MotionCapture::kDefaultVelocitySamples {5}

Default number of velocity samples used for calculations.

This integer value defines the default number of recent velocity samples stored in the velocity queue and used for calculating the filtered velocity of the object.

Definition at line 102 of file motion_capture.hpp.

102{5};

Referenced by loadParameters().

◆ kMillisecondsPerSecond

double pointcloud_motion_capture::MotionCapture::kMillisecondsPerSecond {1000.0}

Conversion factor from seconds to milliseconds.

This double value defines the constant factor for converting seconds to milliseconds. It is used to convert the publish rate or other time-related values in calculations that require time-based units.

Definition at line 128 of file motion_capture.hpp.

128{1000.0};

Referenced by MotionCapture().

◆ point_cloud_topic_filtered_

std::string pointcloud_motion_capture::MotionCapture::point_cloud_topic_filtered_
private

Topic name for subscribing to filtered point cloud data.

This string value holds the name of the topic that the node subscribes to, which provides filtered point cloud data for processing and extracting object information.

Definition at line 386 of file motion_capture.hpp.

Referenced by loadParameters(), and MotionCapture().

◆ position_publish_topic_

std::string pointcloud_motion_capture::MotionCapture::position_publish_topic_
private

Topic name for publishing the calculated position of an object.

This string value holds the name of the topic that the node publishes calculated position data to, as geometry_msgs::msg::Point messages.

Definition at line 394 of file motion_capture.hpp.

Referenced by loadParameters(), and MotionCapture().

◆ position_publisher_

rclcpp::Publisher<geometry_msgs::msg::Point>::SharedPtr pointcloud_motion_capture::MotionCapture::position_publisher_
private

ROS2 publisher to send the calculated object position.

This publisher sends geometry_msgs::msg::Point messages, representing the estimated position of an object derived from the point cloud data. The position is calculated based on the centroid of the object in the point cloud.

Definition at line 264 of file motion_capture.hpp.

Referenced by MotionCapture(), and publishPosition().

◆ position_queue_

std::queue<Eigen::Vector4f> pointcloud_motion_capture::MotionCapture::position_queue_
private

Queue to store recent position samples for calculating position.

This queue holds Eigen::Vector4f values representing the object’s position in the 3D space. The queue size is limited based on the number of position samples specified in the configuration, and is used to compute smoothed or averaged position values over time.

Definition at line 292 of file motion_capture.hpp.

Referenced by getFilteredPosition(), publishData(), and updatePositionSamples().

◆ position_samples_

int pointcloud_motion_capture::MotionCapture::position_samples_
private

Number of position samples used for calculations.

This integer value defines how many recent position samples are stored in the position queue and used for calculating smoothed or averaged position data.

Definition at line 343 of file motion_capture.hpp.

Referenced by loadParameters(), and updatePositionSamples().

◆ previous_position_

Eigen::Vector4f pointcloud_motion_capture::MotionCapture::previous_position_
private

The previous position of the object in 3D space.

This Eigen::Vector4f value stores the last known position of the object, which is used to calculate velocity when new position data is received.

Definition at line 309 of file motion_capture.hpp.

Referenced by publishData(), and publishVelocity().

◆ previous_time_

rclcpp::Time pointcloud_motion_capture::MotionCapture::previous_time_
private

The timestamp of the previous position sample.

This rclcpp::Time object stores the time at which the last position sample was recorded. It is used to compute the time difference between consecutive position updates, which is essential for velocity calculations.

Definition at line 326 of file motion_capture.hpp.

Referenced by publishData(), and publishVelocity().

◆ previous_velocity_

Eigen::Vector3f pointcloud_motion_capture::MotionCapture::previous_velocity_
private

The previous velocity of the object in 3D space.

This Eigen::Vector3f value stores the last known velocity of the object, which is used to calculate acceleration when new velocity data is received.

Definition at line 317 of file motion_capture.hpp.

Referenced by publishAcceleration().

◆ previous_velocity_time_

rclcpp::Time pointcloud_motion_capture::MotionCapture::previous_velocity_time_
private

The timestamp of the previous velocity sample.

This rclcpp::Time object stores the time at which the last velocity sample was recorded. It is used to compute the time difference between consecutive velocity updates, which is essential for acceleration calculations.

Definition at line 335 of file motion_capture.hpp.

Referenced by publishAcceleration().

◆ publish_rate_

double pointcloud_motion_capture::MotionCapture::publish_rate_
private

Publish rate for sending position, velocity, and acceleration data.

This double value specifies the rate, in Hz, at which the publishers send the calculated position, velocity, and acceleration messages. It controls the frequency of updates for the published data.

Definition at line 368 of file motion_capture.hpp.

Referenced by loadParameters(), and MotionCapture().

◆ queue_size_

int pointcloud_motion_capture::MotionCapture::queue_size_
private

Queue size for message publishers and subscriptions.

This integer value specifies the queue size for both publishers and subscriptions, controlling how many messages are stored before being processed or discarded.

Definition at line 359 of file motion_capture.hpp.

Referenced by loadParameters(), and MotionCapture().

◆ subscription_

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

ROS2 subscription to receive PointCloud2 messages.

This subscription listens to a topic that provides filtered point cloud data (sensor_msgs::msg::PointCloud2) and triggers the callback function to process the incoming data, allowing the system to extract relevant information for further use.

Definition at line 255 of file motion_capture.hpp.

Referenced by MotionCapture().

◆ timer_

rclcpp::TimerBase::SharedPtr pointcloud_motion_capture::MotionCapture::timer_
private

Timer used for scheduling the publication of data.

This ROS2 timer triggers the publication of position, velocity, and acceleration data at the rate specified by publish_rate_. The timer ensures regular updates based on the configured time interval.

Definition at line 377 of file motion_capture.hpp.

Referenced by MotionCapture().

◆ velocity_publish_topic_

std::string pointcloud_motion_capture::MotionCapture::velocity_publish_topic_
private

Topic name for publishing the calculated velocity of an object.

This string value holds the name of the topic that the node publishes calculated velocity data to, as geometry_msgs::msg::Vector3 messages.

Definition at line 402 of file motion_capture.hpp.

Referenced by loadParameters(), and MotionCapture().

◆ velocity_publisher_

rclcpp::Publisher<geometry_msgs::msg::Vector3>::SharedPtr pointcloud_motion_capture::MotionCapture::velocity_publisher_
private

ROS2 publisher to send the calculated object velocity.

This publisher sends geometry_msgs::msg::Vector3 messages, representing the estimated velocity of an object. The velocity is computed as the change in position over time, based on sequential position samples.

Definition at line 273 of file motion_capture.hpp.

Referenced by MotionCapture(), and publishVelocity().

◆ velocity_queue_

std::queue<Eigen::Vector3f> pointcloud_motion_capture::MotionCapture::velocity_queue_
private

Queue to store recent velocity samples for calculating velocity.

This queue holds Eigen::Vector3f values representing the object’s velocity in the 3D space. The velocity is calculated based on the change in position between consecutive samples stored in this queue.

Definition at line 301 of file motion_capture.hpp.

Referenced by getFilteredVelocity(), publishData(), and updateVelocitySamples().

◆ velocity_samples_

int pointcloud_motion_capture::MotionCapture::velocity_samples_
private

Number of velocity samples used for calculations.

This integer value defines how many recent velocity samples are stored in the velocity queue and used for calculating smoothed or averaged velocity data.

Definition at line 351 of file motion_capture.hpp.

Referenced by loadParameters(), and updateVelocitySamples().


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