#include <ros/ros.h>
#include <actionlib/server/action_server.h>
#include <pr2_tilt_laser_interface/GetSnapshotAction.h>
#include <pr2_msgs/SetLaserTrajCmd.h>
#include <sensor_msgs/LaserScan.h>
#include <laser_geometry/laser_geometry.h>
#include <pcl_ros/transforms.h>
#include <pcl_conversions/pcl_conversions.h>
#include <tf/transform_listener.h>
#include "tf/message_filter.h"
#include <message_filters/subscriber.h>
#include <pcl/io/io.h>
Go to the source code of this file.
|
void | appendCloud (sensor_msgs::PointCloud2 &dest, const sensor_msgs::PointCloud2 &src) |
|
int | main (int argc, char **argv) |
|
void appendCloud |
( |
sensor_msgs::PointCloud2 & |
dest, |
|
|
const sensor_msgs::PointCloud2 & |
src |
|
) |
| |
int main |
( |
int |
argc, |
|
|
char ** |
argv |
|
) |
| |