00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00032 #include <unistd.h>
00033 
00034 #include <iostream>
00035 #include <string>
00036 #include <vector>
00037 #include <map>
00038 #include <fstream>
00039 
00040 #include <ros/ros.h>
00041 
00042 #include <laser_geometry/laser_geometry.h>
00043 #include <tf/transform_listener.h>
00044 
00045 #include <visualization_msgs/Marker.h>
00046 #include <visualization_msgs/MarkerArray.h>
00047 #include <sensor_msgs/LaserScan.h>
00048 
00049 #include <atlascar_base/AtlascarStatus.h>
00050 #include <atlascar_base/AtlascarPartialStatus.h>
00051 #include <atlascar_base/AtlascarVelocityStatus.h>
00052 
00053 #include <pcl_ros/transforms.h>
00054 #include <pcl/ros/conversions.h>
00055 #include <pcl/point_cloud.h>
00056 #include <pcl/point_types.h>
00057 #include <pcl/segmentation/extract_polygonal_prism_data.h>
00058 #include <pcl/filters/extract_indices.h>
00059 #include <pcl/filters/project_inliers.h>
00060 
00061 using namespace std;
00062 using namespace ros;
00063 
00064 class Conversion
00065 {
00066         public:
00067                 
00068                 Conversion():
00069                 n_("~"),
00070                 listener_(n_,ros::Duration(10))
00071                 {
00072                         laser_1_report_name_ = ros::names::remap("laser_1_report");
00073                         laser_2_report_name_ = ros::names::remap("laser_2_report");
00074                         laser_3_report_name_ = ros::names::remap("laser_3_report");
00075                         
00076                         atlascar_status_report_name_ = ros::names::remap("atlascar_status_report");
00077                         atlascar_velocity_status_report_name_ = ros::names::remap("atlascar_velocity_status_report");
00078                         
00079                         remove(laser_1_report_name_.c_str());
00080                         remove(laser_2_report_name_.c_str());
00081                         remove(laser_3_report_name_.c_str());
00082                         
00083                         remove(atlascar_status_report_name_.c_str());
00084                         remove(atlascar_velocity_status_report_name_.c_str());
00085                         
00086                         laser_1_handler_ = n_.subscribe<sensor_msgs::LaserScan> ("laser_1",1000,boost::bind(&Conversion::laserHandler,this,_1,laser_1_report_name_));
00087                         laser_2_handler_ = n_.subscribe<sensor_msgs::LaserScan> ("laser_2",1000,boost::bind(&Conversion::laserHandler,this,_1,laser_2_report_name_));
00088                         laser_3_handler_ = n_.subscribe<sensor_msgs::LaserScan> ("laser_3",1000,boost::bind(&Conversion::laserHandler,this,_1,laser_3_report_name_));
00089                         
00090                         atlascar_status_handler_ = n_.subscribe("atlascar_status", 1000, &Conversion::atlascarStatusHandler,this);
00091                         atlascar_velocity_status_handler_ = n_.subscribe("atlascar_velocity_status", 1000, &Conversion::atlascarVelocityStatusHandler,this);
00092                 }
00093                 
00094                 ~Conversion()
00095                 {
00096                         
00097                 }
00098                 
00099                 void laserHandler(const sensor_msgs::LaserScan::ConstPtr& scan_in,string report_name)
00100                 {
00101                         sensor_msgs::PointCloud2 cloud;
00102                         
00103                         listener_.waitForTransform(ros::names::remap("base_link"), scan_in->header.frame_id, ros::Time::now(), ros::Duration(10.0));
00104                         
00105                         try
00106                         {
00107                                 projector_.transformLaserScanToPointCloud(ros::names::remap("base_link"),*scan_in,cloud,listener_);
00108                         }
00109                         catch (tf::TransformException ex)
00110                         {
00111                                 cout<<"Error!! "<<ex.what()<<endl;
00112                                 return;
00113                         }
00114                         
00115                         pcl::PointCloud<pcl::PointXYZ> data;
00116                         pcl::fromROSMsg(cloud,data);
00117         
00118                         ofstream report_laser;
00119                         report_laser.open(report_name.c_str(),ios::app);
00120                         
00121                         boost::format fm("%.4f");
00122                         fm % scan_in->header.stamp.toSec();
00123         
00124                         report_laser<<scan_in->header.seq<<" "<<fm.str()<<" "<<ros::names::remap("base_link");
00125                         
00126                         for(pcl::PointCloud<pcl::PointXYZ>::iterator it = data.begin();it!=data.end();it++)
00127                                 report_laser<<" "<<it->x<<" "<<it->y<<" "<<it->z;
00128                         
00129                         report_laser<<endl;
00130         
00131                         report_laser.close();
00132                 }
00133 
00134                 void atlascarStatusHandler(const atlascar_base::AtlascarStatusPtr& status)
00135                 {
00136                         ofstream report_status;
00137                         report_status.open(atlascar_status_report_name_.c_str(),ios::app);
00138                         
00139                         boost::format fm_stamp("%.4f");
00140                         fm_stamp % status->header.stamp.toSec();
00141         
00142                         report_status<<status->header.seq<<" "<<fm_stamp.str()<<" ";
00143                         
00144                         boost::format fm_data("%.6f %.6f %.6f %.6f %.6f %.6f");
00145                         fm_data % status->throttle % status->brake % status->clutch % status->steering_wheel % status->speed % status->rpm;
00146                         
00147                         report_status<<fm_data.str()<<endl;
00148                 }
00149 
00150 
00151                 void atlascarVelocityStatusHandler(const atlascar_base::AtlascarVelocityStatusPtr& status)
00152                 {
00153                         ofstream report_status;
00154                         report_status.open(atlascar_velocity_status_report_name_.c_str(),ios::app);
00155                         
00156                         boost::format fm_stamp("%.4f");
00157                         fm_stamp % status->header.stamp.toSec();
00158         
00159                         report_status<<status->header.seq<<" "<<fm_stamp.str()<<" ";
00160                         
00161                         boost::format fm_data("%.1f %.6f %.6f %.6f");
00162                         fm_data % status->counting % status->pulses_sec % status->revolutions_sec % status->velocity;
00163                         
00164                         report_status<<fm_data.str()<<endl;
00165                         
00166                 }
00167                 
00168                 string laser_1_report_name_;
00169                 string laser_2_report_name_;
00170                 string laser_3_report_name_;
00171                 string atlascar_status_report_name_;
00172                 string atlascar_velocity_status_report_name_;
00173                 
00174                 ros::Subscriber laser_1_handler_; 
00175                 ros::Subscriber laser_2_handler_;
00176                 ros::Subscriber laser_3_handler_;
00177 
00178                 ros::Subscriber atlascar_status_handler_;
00179                 ros::Subscriber atlascar_velocity_status_handler_;
00180                 
00181                 ros::NodeHandle n_;
00182                 tf::TransformListener listener_;
00183                 laser_geometry::LaserProjection projector_;
00184 };
00185 
00186 int main(int argc,char**argv)
00187 {
00188         ros::init(argc, argv, "conversion");
00189                         
00190         Conversion convert;
00191         
00192         cout<<"spining ..."<<endl;
00193         ros::spin();
00194         
00195         return 0;
00196 }