20 #include "leica_scanstation_msgs/PointCloudFile.h"    21 #include "leica_scanstation_utils/LeicaUtils.h"    40     bool serviceCb(leica_scanstation_msgs::PointCloudFile::Request& req,
    41                    leica_scanstation_msgs::PointCloudFile::Response& res)
    43         ROS_INFO(
"Request to publish clouds");
    45         int r = 
loadCloud(req.source_cloud_file, source_cloud_msg_, 255, 0, 128);
    46         if(r==-1) 
return false;
    48         r = 
loadCloud(req.target_cloud_file, target_cloud_msg_, 0, 0, 255);
    49         if(r==-1) 
return false;
    53         res.message = 
"Finished service to receive cloud";
    59                   sensor_msgs::PointCloud2& cloud_msg,
    64         std::string extension = boost::filesystem::extension(file_name);
    66         std::string 
f = LeicaUtils::getFilePath(file_name);
    67         if (file_name.empty() || extension.empty() || !boost::filesystem::exists(f))
    69             ROS_ERROR(
"Couldn't read file %s", f.c_str());
    73         if (extension==
".pcd")
    75             pcl::io::loadPCDFile<pcl::PointXYZRGB>(f, *cloud);
    79         else if (extension==
".ply" || extension==
".obj")
    81             int sample_points = 500000;
    88             ROS_ERROR(
"Couldn't read file %s", f.c_str());
    90         ROS_INFO(
"Loaded file: %s", f.c_str());
    98 int main(
int argc, 
char** argv)
   100     ros::init(argc, argv, 
"cloud_publisher");
   103     std::string pointcloud_folder_path;
   104     if (!nh.
getParam(
"/pointcloud_folder", pointcloud_folder_path))
   106         pointcloud_folder_path = LeicaUtils::findPointcloudFolderPath();
   109     ROS_INFO(
"Search for pointcloud in %s", pointcloud_folder_path.c_str());
   118     ROS_INFO(
"Service waiting for call to /publish_clouds");
   126             pub.
publish(cl.source_cloud_msg_);
   128             tar_pub.publish(cl.target_cloud_msg_);
 
pcl::PointCloud< pcl::PointXYZRGB > PointCloudRGB
bool serviceCb(leica_scanstation_msgs::PointCloudFile::Request &req, leica_scanstation_msgs::PointCloudFile::Response &res)
const std::string SOURCE_CLOUD_TOPIC
sensor_msgs::PointCloud2 target_cloud_msg_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
pcl::PointCloud< pcl::PointXYZ > PointCloudXYZ
static void colorizeCloud(PointCloudRGB::Ptr cloud_rgb, int R, int G, int B)
Apply RGB values to cloud. 
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
static bool isValidCloud(PointCloudXYZ::Ptr cloud)
Check whether cloud contains data and is not empty. 
int main(int argc, char **argv)
const std::string TARGET_CLOUD_TOPIC
void publish(const boost::shared_ptr< M > &message) const
static void cloudToROSMsg(PointCloudRGB::Ptr cloud, sensor_msgs::PointCloud2 &cloud_msg, const std::string &frameid="world")
Convert XYZRGB cloud to PointCloud2. 
bool getParam(const std::string &key, std::string &s) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
This class is used to obtain pcl::PointCloud from CAD file. Supported formats: .OBJ. 
void convertCloud(PointCloudRGB::Ptr cloud)
convert cloud defined by path in construstor into cloud 
ROSCPP_DECL void spinOnce()
static bool isValidCloudMsg(const sensor_msgs::PointCloud2 &cloud_msg)
Check whether PointCloud2 contains data and is not empty. 
sensor_msgs::PointCloud2 source_cloud_msg_
pcl::PointCloud< pcl::PointXYZRGB > PointCloudRGB
int loadCloud(const std::string &file_name, sensor_msgs::PointCloud2 &cloud_msg, int R, int G, int B)