get_tables_client.cpp
Go to the documentation of this file.
00001 
00059 //##################
00060 //#### includes ####
00061 
00062 //standard includes
00063 #include <iostream>
00064 #include <fstream>
00065 #include <sstream>
00066 
00067 //ros includes
00068 #include "ros/ros.h"
00069 #include <rosbag/bag.h>
00070 
00071 // ROS message includes
00072 #include <cob_3d_mapping_msgs/GetObjectsOfClass.h>
00073 #include <cob_3d_mapping_msgs/ShapeArray.h>
00074 
00075 // PCL includes
00076 #include <pcl/io/pcd_io.h>
00077 #include <pcl/point_types.h>
00078 #include <pcl_conversions/pcl_conversions.h>
00079 #include <pcl/conversions.h>
00080 
00081 class TablesClient
00082 {
00083 public:
00084   // Constructor
00085   TablesClient ()
00086 
00087   {
00088     get_tables_client_ = nh.serviceClient<cob_3d_mapping_msgs::GetObjectsOfClass> ("get_objects_of_class");
00089    pc2_pub_ = nh.advertise<sensor_msgs::PointCloud2> ("/get_tables_client/point_cloud2", 100);
00090     ros::param::param ("~file_path", file_path_, std::string ("/home/goa-wq/tmp/"));
00091     ros::param::param ("~save_txt_file", save_txt_file_, true);
00092     ros::param::param ("~save_pcd_file", save_pcd_file_, true);
00093     ros::param::param ("~save_bag_file", save_bag_file_, true);
00094 
00095     std::cout << "ROS_PARAM: file_path = " << file_path_ << std::endl;
00096     ROS_INFO("ROS_PARAM: save_txt_file = %d",save_txt_file_);
00097     ROS_INFO("ROS_PARAM: save_pcd_file = %d",save_pcd_file_);
00098     ROS_INFO("ROS_PARAM: save_bag_file = %d",save_bag_file_);
00099   }
00100 
00101   // Destructor
00102   ~TablesClient ()
00103   {
00105   }
00106 
00112   void
00113   callService ()
00114   {
00115     ROS_INFO("waiting for server to start");
00116     ros::service::waitForService ("get_objects_of_class");
00117     //build message
00118     cob_3d_mapping_msgs::GetObjectsOfClassRequest req;
00119     cob_3d_mapping_msgs::GetObjectsOfClassResponse res;
00120     get_tables_client_.call (req, res);
00121     ROS_INFO("Service call finished");
00122     saveTables (res);
00123   }
00124 
00132   void
00133   saveTables (cob_3d_mapping_msgs::GetObjectsOfClass::Response &res)
00134   {
00135     ROS_INFO("Table objects received : %d",res.objects.shapes.size ());
00136     if (save_txt_file_ || save_pcd_file_)
00137     {
00138       for (unsigned int i = 0; i < res.objects.shapes.size (); i++)
00139       {
00140         if (save_txt_file_ == true && res.objects.shapes.size() > 0)
00141         {
00142           std::ofstream object_file;
00143           std::stringstream ss;
00144           ROS_INFO("Saving Table object: table_ %d",i);
00145           ss << file_path_ << "table_" << i << ".txt";
00146           object_file.open (ss.str ().c_str ());
00147           object_file << "#Table Points\n";
00148           object_file << res.objects.shapes[i] << "\n";
00149           object_file.close ();
00150           ROS_INFO("Text file saved");
00151         }
00152         if (save_pcd_file_ == true && res.objects.shapes.size() > 0)
00153         {
00154           for (unsigned int j = 0; j < res.objects.shapes[i].points.size (); j++)
00155           {
00156             ROS_INFO("Saving Table object: table_%d_%d",i,j);
00157             std::stringstream ss1;
00158             ss1 << file_path_ << "table_" << i << "_" << j << ".pcd";
00159             pcl::PointCloud<pcl::PointXYZ> p;
00160             pcl::PCLPointCloud2 p2;
00161             pcl_conversions::toPCL(res.objects.shapes[i].points[j], p2);
00162             pcl::fromPCLPointCloud2(p2, p);
00163             //pcl::fromROSMsg (res.objects.shapes[i].points[j], p);
00164             pcl::io::savePCDFile (ss1.str (), p, false);
00165             ROS_INFO("PCD file saved");
00166           }
00167         }
00168 
00169       }
00170     }
00171 
00172     if (save_bag_file_ == true && res.objects.shapes.size() > 0)
00173     {
00174       cob_3d_mapping_msgs::ShapeArray sa;// = res.objects.shapes;
00175       sa.header.stamp = ros::Time (1.0);
00176 
00177       sa.header.frame_id = "/map";
00178       for (unsigned int i = 0; i < res.objects.shapes.size (); i++)
00179       {
00180         sa.shapes.push_back (res.objects.shapes[i]);
00181         /*
00182         for (unsigned int j = 0; j < res.objects.shapes[i].points.size (); j++)
00183         {
00184           sensor_msgs::PointCloud2 pc2;
00185           pc2 = res.objects.shapes[i].points[j];
00186           pc2.header.frame_id = "/map";
00187           pc2_pub_.publish(pc2);
00188           ros::Duration(10).sleep();
00189         }
00190         */
00191       }
00192 
00193     rosbag::Bag bag;
00194     std::stringstream ss1;
00195     ss1 << file_path_ << "table.bag";
00196     bag.open (ss1.str().c_str(), rosbag::bagmode::Write);
00197     bag.write ("/get_tables_client/shape_array", sa.header.stamp, sa);
00198     bag.close ();
00199     ROS_INFO("BAG file saved");
00200   }
00201     else
00202       ROS_INFO("No table object : BAG file not saved");
00203 
00204 }
00205 
00206 ros::NodeHandle nh;
00207 
00208 protected:
00209 ros::ServiceClient get_tables_client_;
00210 ros::Publisher pc2_pub_;
00211 
00212 std::string file_path_;
00213 bool save_txt_file_;
00214 bool save_pcd_file_;
00215 bool save_bag_file_;
00216 
00217 };
00218 
00219 int
00220 main (int argc, char **argv)
00221 {
00222   ros::init (argc, argv, "client");
00223 
00224   TablesClient client;
00225   client.callService ();
00226 
00227   //ros::spin ();
00228   return 0;
00229 }
00230 


cob_3d_mapping_semantics
Author(s): Georg Arbeiter
autogenerated on Wed Aug 26 2015 11:03:34