transform_cloud_nodelet.cpp
Go to the documentation of this file.
1 /**************************************************************************************************
2  Software License Agreement (BSD License)
3 
4  Copyright (c) 2011-2013, LAR toolkit developers - University of Aveiro - http://lars.mec.ua.pt
5  All rights reserved.
6 
7  Redistribution and use in source and binary forms, with or without modification, are permitted
8  provided that the following conditions are met:
9 
10  *Redistributions of source code must retain the above copyright notice, this list of
11  conditions and the following disclaimer.
12  *Redistributions in binary form must reproduce the above copyright notice, this list of
13  conditions and the following disclaimer in the documentation and/or other materials provided
14  with the distribution.
15  *Neither the name of the University of Aveiro nor the names of its contributors may be used to
16  endorse or promote products derived from this software without specific prior written permission.
17 
18  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
19  IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
20  FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
21  CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
22  DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
23  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER
24  IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
25  OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 ***************************************************************************************************/
27 
28 
36 #include <ros/ros.h>
37 #include <sensor_msgs/PointCloud2.h>
38 #include <tf/transform_listener.h>
39 #include <pcl/conversions.h>
40 #include <pcl/point_cloud.h>
41 #include <pcl/point_types.h>
42 #include <pcl_ros/transforms.h>
43 #include <pcl_conversions/pcl_conversions.h>
44 
45 #define PFLN printf("Line=%d\n", __LINE__);
46 
47 using namespace std;
48 
49 // Declare a publisher
50 
51 ros::Publisher pub;
52 string frame_id;
53 tf::TransformListener *listener_center_bumper_ptr;
54 
55 
56 void topic_callback(const sensor_msgs::PointCloud2ConstPtr& msg)
57 {
58  static int counter=0; counter++;
59  ROS_INFO("Message received n= %d",counter);
60 
61  // Pcl clouds
62  pcl::PointCloud<pcl::PointXYZRGB> cloud_in;
63  pcl::PointCloud<pcl::PointXYZRGB> cloud_trans;
64 
65  //STEP 0 Convert sensor_msgs to pcl
66 // pcl::fromROSMsg(*msg,cloud_in);
67 
68  pcl::PCLPointCloud2 pcl_pc;
69  pcl_conversions::toPCL(*msg, pcl_pc);
70  pcl::fromPCLPointCloud2(pcl_pc, cloud_in);
71 
72  //STEP 1 Convert xb3 message to center_bumper frame (i think it is better this way)
73  tf::StampedTransform transform;
74  try
75  {
76  listener_center_bumper_ptr->lookupTransform(frame_id, msg->header.frame_id, ros::Time(0), transform);
77  }
78  catch (tf::TransformException ex)
79  {
80  ROS_ERROR("%s",ex.what());
81  }
82 
83  // Transform point cloud
84  pcl_ros::transformPointCloud (cloud_in,cloud_trans,transform);
85  cloud_trans.header.frame_id=frame_id; // Must set new frame manually
86  sensor_msgs::PointCloud2 msg_pub;
87 
88  pcl::toROSMsg(cloud_trans, msg_pub);
89  pub.publish(msg_pub);
90 }
91 
92 
93 int main(int argc, char **argv)
94 {
95  ROS_INFO("Started transform cloud nodelet");
96  ros::init(argc,argv,"transform_cloud_nodelet");
97 
98  ros::NodeHandle n;
99 
100  tf::TransformListener listener_center_bumper; // atc/vehicle/center_bumper
101  listener_center_bumper_ptr=&listener_center_bumper;
102 
103  // Getting point cloud from launch file
104  string pointcloud_subscribed;
105  if (!n.hasParam("pointcloud_to_transform"))
106  {
107  ROS_ERROR("Must set properly a input pointcloud");
108  return -1;
109  }
110  else
111  n.getParam("pointcloud_to_transform", pointcloud_subscribed);
112 
113  // Getting reference frame to transform
114  if (!n.hasParam("frame_id"))
115  {
116  ROS_ERROR("Must set properly a frame_id to transform");
117  return -1;
118  }
119  else
120  n.getParam("frame_id", frame_id);
121 
122  // Getting reference frame to transform
123  string pointcloud_transformed;
124  if (!n.hasParam("pointcloud_transformed"))
125  {
126  ROS_ERROR("Must set properly a topic to publish the transformed cloud");
127  return -1;
128  }
129  else
130  n.getParam("pointcloud_transformed", pointcloud_transformed);
131 
132  ros::Subscriber sub = n.subscribe(pointcloud_subscribed, 1, topic_callback);
133  pub=n.advertise<sensor_msgs::PointCloud2>(pointcloud_transformed,1000);
134 
135  ros::spin();
136  return 1;
137 
138 
139 }
int main(int argc, char **argv)
ros::Publisher pub
void topic_callback(const sensor_msgs::PointCloud2ConstPtr &msg)
string frame_id
tf::TransformListener * listener_center_bumper_ptr


plane_model_road_segmentation
Author(s): Tiago Talhada
autogenerated on Mon Mar 2 2015 01:32:38