![]() |
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 <motion_capture.hpp>
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 ¢roid) |
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 ¢roid) |
Publishes the object's position to a ROS topic. | |
Eigen::Vector3f | publishVelocity (const Eigen::Vector4f ¤t_position) |
Publishes the object's velocity to a ROS topic. | |
void | publishAcceleration (const Eigen::Vector3f ¤t_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. | |
Definition at line 22 of file motion_capture.hpp.
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.
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.
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.
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_.
|
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.
Definition at line 78 of file motion_capture.cpp.
References position_queue_.
Referenced by publishData().
|
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.
Definition at line 97 of file motion_capture.cpp.
References velocity_queue_.
Referenced by publishData().
|
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.
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().
|
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.
msg | Shared pointer to the received sensor_msgs::msg::PointCloud2 message. |
Definition at line 59 of file motion_capture.cpp.
References updatePositionSamples().
Referenced by MotionCapture().
|
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.
current_velocity | The current velocity of the object in 3D space, represented as Eigen::Vector3f. |
Definition at line 162 of file motion_capture.cpp.
References acceleration_publisher_, kVectorX, kVectorY, kVectorZ, previous_velocity_, and previous_velocity_time_.
Referenced by 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.
References getFilteredPosition(), getFilteredVelocity(), position_queue_, previous_position_, previous_time_, publishAcceleration(), publishPosition(), publishVelocity(), updateVelocitySamples(), and velocity_queue_.
Referenced by MotionCapture().
|
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.
centroid | The centroid of the object in 3D space, represented as Eigen::Vector4f. |
Definition at line 127 of file motion_capture.cpp.
References kCentroidX, kCentroidY, kCentroidZ, and position_publisher_.
Referenced by publishData().
|
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.
current_position | The current position of the object in 3D space, represented as Eigen::Vector4f. |
Definition at line 137 of file motion_capture.cpp.
References kCentroidX, kCentroidY, kCentroidZ, previous_position_, previous_time_, and velocity_publisher_.
Referenced by publishData().
|
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.
centroid | The centroid of the object in 3D space, represented as Eigen::Vector4f. |
Definition at line 70 of file motion_capture.cpp.
References position_queue_, and position_samples_.
Referenced by pointCloudCallback().
|
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.
velocity | The velocity of the object in 3D space, represented as Eigen::Vector3f. |
Definition at line 89 of file motion_capture.cpp.
References velocity_queue_, and velocity_samples_.
Referenced by publishData().
|
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().
|
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().
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.
Referenced by loadParameters().
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.
Referenced by loadParameters().
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.
Referenced by loadParameters().
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.
Referenced by loadParameters().
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.
Referenced by loadParameters().
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.
Referenced by loadParameters().
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.
Referenced by loadParameters().
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.
Referenced by loadParameters().
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.
Referenced by MotionCapture().
|
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().
|
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().
|
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().
|
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().
|
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().
|
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().
|
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().
|
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().
|
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().
|
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().
|
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().
|
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().
|
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().
|
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().
|
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().
|
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().
|
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().