How to use pcl_ros::transformPointCloud in ROS 2?
I am currently working on a porting a package in ROS 1 Noetic to ROS 2 Foxy which involves transforming the point clouds for that part there is a function pcl_ros::transformPointCloud
in pcl_ros
package in ROS 1. I want to use it in ROS 2.
I tried using pcl_ros::transformPointCloud
, but it throws error in pcl::fromROSMsg
and pcl::toROSMsg
. In ROS 2, I am converting between sensormsgs and point cloud which requires `pclconversions` package. Please help me what should I do here ?
Below is my node :
#include <memory>
#include <iostream>
#include <string>
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
#include <map>
#include <vector>
#include "sensor_msgs/msg/point_cloud2.hpp"
#include "builtin_interfaces/msg/time.hpp"
#include "builtin_interfaces/msg/duration.hpp"
#include <pcl_conversions/pcl_conversions.h>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl_ros/transforms.h>
#include "tf2/exceptions.h"
#include "tf2_ros/transform_listener.h"
#include "tf2_ros/buffer.h"
#include "tf2/convert.h"
#include "geometry_msgs/msg/transform_stamped.hpp"
#include "geometry_msgs/msg/twist.hpp"
using namespace std;
// Combine Clouds Class : To combine point cloud from two ifm3d sensors
class ROS2CombineClouds : public rclcpp::Node
{
public:
ROS2CombineClouds() : Node("ros2_combine_clouds")
{
// Publishing and subscribing topics
cloud_topic = "/ifm3d/leftcam_d/cloud";
cloud_topic1 = "/ifm3d/rightcam_d/cloud";
out_topic = "/cloud";
target_frame = "base_link";
tf_buffer_ = std::make_shared<tf2_ros::Buffer>(this->get_clock());
cloudSubs = {};
RCLCPP_INFO(this->get_logger(), "Subscribing to %s", s.c_str());
cloud_sub = this->create_subscription<sensor_msgs::msg::PointCloud2>(
cloud_topic, 10, std::bind(&ROS2CombineClouds::topic_callback, this, std::placeholders::_1));
cloudSubs.push_back(cloud_sub);
cloud_sub = this->create_subscription<sensor_msgs::msg::PointCloud2>(
cloud_topic1, 10, std::bind(&ROS2CombineClouds::topic_callback, this, std::placeholders::_1));
cloudSubs.push_back(cloud_sub);
cloud_pub = this->create_publisher<sensor_msgs::msg::PointCloud2>(out_topic, 10);
}
private:
void topic_callback(const sensor_msgs::msg::PointCloud2::SharedPtr input) const
{
// Check if rgb in message fields
auto color_cloud = false;
for (const auto& element : input->fields)
{
if (element.name == "rgb")
{
color_cloud = true;
}
}
// Call combine with appropriate pointcloud type
if (!color_cloud)
{
static std::map<std::string, pcl::PointCloud<pcl::PointXYZ>::Ptr> clouds;
// Defining different types of point cloud
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_t(new pcl::PointCloud<pcl::PointXYZ>);
// convert from ros msg to point cloud
pcl::fromROSMsg(*input, *cloud);
// geometry msgs
geometry_msgs::msg::TransformStamped tr;
sensor_msgs::msg::PointCloud2::SharedPtr output;
try
{
tr = tf_buffer_->lookupTransform((*input).header.frame_id, target_frame,
tf2_ros::fromMsg((*input).header.stamp));
}
catch (tf2::LookupException& e)
{
RCLCPP_ERROR(rclcpp::get_logger("pcl_ros"), "%s", e.what());
return;
}
if (pcl_ros::transformPointCloud(target_frame, *cloud, *cloud_t, *tf_buffer_))
{
clouds[(*input).header.frame_id] = (cloud_t);
}
else
{
RCLCPP_INFO(this->get_logger(), "Cloud Transform error!");
return;
}
// Wait until all clouds have been received to publish
if (clouds.size() != cloudSubs.size())
return;
pcl::PointCloud<pcl::PointXYZ>::Ptr summed_cloud(new pcl::PointCloud<pcl::PointXYZ>);
for (auto i = clouds.begin(); i != clouds.end(); i++)
*summed_cloud += *(i->second);
// Publish sensor_msgs::msg::PointCloud2 with summed cloud
sensor_msgs::msg::PointCloud2 sum_msg;
pcl::toROSMsg(*summed_cloud, sum_msg);
sum_msg.header.frame_id = target_frame;
sum_msg.fields = input->fields;
cloud_pub->publish(sum_msg);
RCLCPP_INFO(this->get_logger(), "Publishing combined clouds");
// clouds.clear();
}
}
std::istringstream f;
std::string s;
// Vector to store all the subscribers
std::vector<rclcpp::Subscription<sensor_msgs::msg::PointCloud2>::SharedPtr> cloudSubs;
// Publisher
rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr cloud_pub;
// Subscriber
rclcpp::Subscription<sensor_msgs::msg::PointCloud2>::SharedPtr cloud_sub;
// tf2 listener
std::shared_ptr<tf2_ros::TransformListener> tf_listener_{ nullptr };
std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
std::string cloud_topic, out_topic, target_frame, cloud_topic1;
};
int main(int argc, char* argv[])
{
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<ROS2CombineClouds>());
rclcpp::shutdown();
return 0;
}
Asked by advaitpatole@gmail.com on 2022-10-12 13:26:46 UTC
Comments
sensor_msgs::msg::PointCloud2
instead ofpcl::PointCloud
. An example can be found perception_pcl/pcl_ros/tools/bag_to_pcd.cpp#L131.Asked by ravijoshi on 2022-10-14 06:24:52 UTC