Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

support for ROS Kinetic and newer; publishing cloud as shared pointer #1

Open
wants to merge 1 commit into
base: hydro
Choose a base branch
from
Open
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
44 changes: 30 additions & 14 deletions src/transform_pointcloud.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,19 @@
#include <ros/ros.h>
#include <sensor_msgs/PointCloud2.h>
#include <tf/transform_listener.h>

#include <pcl/pcl_base.h>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>

#include <pcl_conversions/pcl_conversions.h>

#include <pcl_ros/transforms.h>
#include <pcl_ros/point_cloud.h>




#include <pluginlib/class_list_macros.h>

namespace grull_transform_pointcloud {
Expand All @@ -12,30 +24,34 @@ namespace grull_transform_pointcloud {
ros::Subscriber sub;
std::string target_frame;
tf::TransformListener listener;

void callback(const sensor_msgs::PointCloud2::ConstPtr &msg) {
sensor_msgs::PointCloud2 output;
output.header.stamp = msg->header.stamp;//ros::Time::now();
sensor_msgs::PointCloud2::Ptr output = boost::make_shared<sensor_msgs::PointCloud2>();

try {
// listener.waitForTransform(target_frame, msg->header.frame_id, msg->header.stamp, ros::Duration(0.5));
listener.waitForTransform(target_frame, msg->header.frame_id, ros::Time(0), ros::Duration(10.0), ros::Duration(0.01));
if (pcl_ros::transformPointCloud(target_frame, *msg, output, listener)) {
// listener.waitForTransform(target_frame, msg->header.frame_id, msg->header.stamp, ros::Duration(0.5));
// listener.waitForTransform(target_frame, msg->header.frame_id, ros::Time(0), ros::Duration(10.0), ros::Duration(0.01))
if (pcl_ros::transformPointCloud(target_frame, *msg, *output, listener)) {
output->header.stamp = msg->header.stamp;//ros::Time::now();
pub.publish(output);
}
} catch (tf::TransformException ex) {
ROS_ERROR("%s",ex.what());
} catch (const tf::TransformException & ex) {
ROS_ERROR_STREAM(ex.what());
}
}

public:
virtual void onInit() {
getPrivateNodeHandle().getParam("target_frame", target_frame);
ros::NodeHandle n = getNodeHandle();
virtual void onInit() override {

ros::NodeHandle & n = getNodeHandle();
ros::NodeHandle & pn = getPrivateNodeHandle();


target_frame = pn.param<std::string>("target_frame", "");
pub = n.advertise<sensor_msgs::PointCloud2>("output_topic", 1, true);
sub = n.subscribe("input_topic", 1,&transform_pointcloud::callback, this);
sub = n.subscribe("input_topic", 1, &transform_pointcloud::callback, this);
}
};
}

PLUGINLIB_DECLARE_CLASS(grull_transform_pointcloud, transform_pointcloud,
grull_transform_pointcloud::transform_pointcloud, nodelet::Nodelet);

PLUGINLIB_EXPORT_CLASS(grull_transform_pointcloud::transform_pointcloud, nodelet::Nodelet);