odom_pc.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  * Copyright (c) 2013, Intelligent Robotics Lab, DLUT.
00004  * All rights reserved.
00005  *
00006  * Redistribution and use in source and binary forms, with or without
00007  * modification, are permitted provided that the following conditions are met:
00008  *
00009  *     * Redistributions of source code must retain the above copyright
00010  *       notice, this list of conditions and the following disclaimer.
00011  *     * Redistributions in binary form must reproduce the above copyright
00012  *       notice, this list of conditions and the following disclaimer in the
00013  *       documentation and/or other materials provided with the distribution.
00014  *     * Neither the name of the Willow Garage, Inc. and Intelligent Robotics 
00015  *        Lab, DLUT nor the names of its contributors may be used to endorse or
00016  *       promote products derived from this software without specific prior written 
00017  *       permission.
00018  *
00019  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00020  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00021  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00022  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00023  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00024  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00025  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00026  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00027  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00028  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00029  * POSSIBILITY OF SUCH DAMAGE.
00030 *********************************************************************/
00031 
00032 #include <ros/ros.h>
00033 #include <sensor_msgs/LaserScan.h>
00034 #include <dlut_pc_odom/motor.h>
00035 #include <std_msgs/Bool.h>
00036 #include <std_msgs/UInt32.h>
00037 #include <geometry_msgs/PointStamped.h>
00038 #include <geometry_msgs/Vector3.h>
00039 
00040 //#include <geometry_msgs/Point32.h>
00041 
00042 #include <iostream>
00043 #include <fstream>
00044 #include <math.h>
00045 
00046 #include <tf/transform_listener.h>
00047 #include <nav_msgs/Odometry.h>
00048 
00049 #include <pcl_ros/point_cloud.h>
00050 #include <pcl/point_types.h>
00051 #include "pcl/io/pcd_io.h"
00052 
00053 #define PAI 3.1415926
00054 
00055 typedef pcl::PointXYZRGB PointType;
00056 typedef pcl::PointCloud<PointType> PCLPointCloud;
00057 PCLPointCloud::Ptr final(new PCLPointCloud);//convert to PointCloud2 to publish
00058 
00059 class PointCloudOdom
00060 {
00061 public:
00062   PointCloudOdom();
00063   ~PointCloudOdom();
00064 
00065   void scanCallBack(const sensor_msgs::LaserScan &ls);
00066   void motorRotateStart(const std_msgs::Bool &is_run);
00067   void motorParamGet(const dlut_pc_odom::motor &motor_msg);
00068   void odomGet(const nav_msgs::Odometry &odom);
00069 
00070   geometry_msgs::Vector3 rpyGet(const tf::Quaternion &qua);
00071   geometry_msgs::Vector3 rpyGet(const geometry_msgs::Quaternion &qua);
00072 
00073   ros::NodeHandle nh_;
00074 
00075 private:
00076   ros::Publisher point_cloud2_pub_;//publish the PointCloud and PointCloud2 message
00077 
00078   ros::Subscriber laser_scan_sub_,rotate_start_sub_,motor_param_sub_,odom_sub_;
00079 
00080   std_msgs::Bool is_rotate_;//message which show the sick begin to rotate or not 
00081   dlut_pc_odom::motor motor_param_;//motor's parameters
00082   sensor_msgs::PointCloud odom_cloud_;//the point cloud corrected by odom
00083 
00084   ros::Time time_begin_rotate_,time_end_rotate_;//the time which the sick begin to rotate and stop to rotate
00085 
00086   double angle_rotated_;//the angle which the sick rotated
00087   bool is_first_flag_;//whether the first data after the sick rotated
00088   unsigned int num_points_;//the points num of the cloud
00089   
00090   unsigned int laser_seq_;//the sequence number of the laser data
00091   unsigned int num_per_cloud_;//the scan number of one cloud
00092   unsigned int points_per_scan_;//the points number per scan
00093 
00094   std::ofstream pc_data_,laser_range_data_;
00095   tf::TransformListener odom_tf_listener_;
00096   std::ofstream odom_data_;
00097 
00098   geometry_msgs::Vector3 ypr_;//yaw,pitch,roll
00099 
00100   double alpha_,beta_,gamma_,length_;//the parameters of the hokuyo platform
00101   double h2p_a_,h2p_b_,h2p_c_,h2p_d_,h2p_e_,h2p_f_,h2p_g_,h2p_h_,h2p_i_;//hokuyo激光到云台变换矩阵R中的值
00102   double p2r_a_,p2r_b_,p2r_c_,p2r_d_,p2r_e_,p2r_f_,p2r_g_,p2r_h_,p2r_i_;//云台到机器人变换矩阵R中的值
00103   double t_h2p_a_,t_h2p_b_,t_h2p_c_;//云台到激光的平移矩阵T
00104 
00105   bool is_first_circle_;//是否是第一圈激光数据
00106   
00107   PointType point2_;//save a temporary point
00108 };
00109 
00110 PointCloudOdom::PointCloudOdom()
00111 {
00112   laser_scan_sub_ = nh_.subscribe("scan", 1000, &PointCloudOdom::scanCallBack,this);
00113   rotate_start_sub_ = nh_.subscribe("is_run_pch", 1, &PointCloudOdom::motorRotateStart,this);
00114   motor_param_sub_ = nh_.subscribe("motor_param", 1000, &PointCloudOdom::motorParamGet,this);
00115   odom_sub_ = nh_.subscribe("odom", 1000, &PointCloudOdom::odomGet,this);
00116   point_cloud2_pub_ = nh_.advertise<PCLPointCloud> ("hokuyo_point_cloud2", 1);
00117   //point_stamp_pub = nh_.advertise<geometry_msgs::PointStamped>("point_stamp", 1000);
00118   
00119   is_rotate_.data = false;
00120   angle_rotated_ = 0.0;
00121 
00122   is_first_flag_ = false;
00123         
00124   num_points_ = 0;
00125   laser_seq_ = 0;
00126 
00127   odom_data_.open("odometry.txt");
00128   laser_range_data_.open("range.txt");
00129   pc_data_.open("odom_pch.txt");
00130   pc_data_<<"//////////////////////////////////////////////////////////////////////////"<<"\n";
00131   pc_data_<<"// 3D Laser Scanning Data File Format: *.3dld"<<"\n";
00132   pc_data_<<"// Designed by: Dong Bingbing  Version 0.0"<<"\n";
00133   pc_data_<<"// Copyright (C) 2013 by DUT-RCIC. All rights reserved."<<"\n";
00134   pc_data_<<"//////////////////////////////////////////////////////////////////////////"<<"\n";
00135   pc_data_<<"//"<<"\n";
00136   pc_data_<<"BEGIN_HEADER"<<"\n";
00137   pc_data_<<"0                  // ScanID"<<"\n";
00138   pc_data_<<"Data               // ScanName"<<"\n";
00139   pc_data_<<"HSR5995TG          // ScannerType"<<"\n";
00140   pc_data_<<"8.000                      // MaxDistance"<<"\n";
00141   pc_data_<<"0                  // IsPoseCal"<<"\n";
00142   pc_data_<<"0                  // IsColored"<<"\n";
00143 
00144   alpha_ = 0.0095;
00145   beta_ = 0.0017;
00146   gamma_ = -0.0262;
00147   length_ = -0.0040;
00148 
00149   h2p_a_ = cos(beta_)*cos(gamma_) - sin(alpha_)*sin(beta_)*sin(gamma_);
00150   h2p_b_ = -cos(beta_)*sin(gamma_) - sin(alpha_)*sin(beta_)*cos(gamma_);
00151   h2p_c_ = -cos(alpha_)*sin(beta_);
00152   h2p_d_ = cos(alpha_)*sin(gamma_);
00153   h2p_e_ = cos(alpha_)*cos(gamma_);
00154   h2p_f_ = -sin(alpha_);
00155   h2p_g_ = sin(beta_)*cos(gamma_) + sin(alpha_)*cos(beta_)*sin(gamma_);
00156   h2p_h_ = -sin(beta_)*sin(gamma_) + sin(alpha_)*cos(beta_)*cos(gamma_);
00157   h2p_i_ = cos(alpha_)*cos(beta_);
00158 
00159   p2r_a_ = 0.999942368044831;   p2r_b_ = 0.00616103270670958;   p2r_c_ = 0.00879217065821694;
00160   p2r_d_ = -0.00613654752375238;p2r_e_ = 0.999977225469970;     p2r_f_ = -0.00280915038216528;
00161   p2r_g_ = -0.00880927768804484;p2r_h_ = 0.00275503491225531;   p2r_i_ = 0.999957402297342;
00162   
00163   t_h2p_a_ = -0.143284347080846;t_h2p_b_ = -0.00961421703449155;t_h2p_c_ = 0.575167371824827;
00164 
00165   is_first_circle_ = true;
00166 }
00167 
00168 PointCloudOdom::~PointCloudOdom()
00169 {
00170   pc_data_<<"END_3D_LASER_DATA"<<"\n";          
00171   pc_data_.close();
00172 
00173   laser_range_data_.close();
00174   odom_data_.close();
00175 }
00176 
00177 void PointCloudOdom::scanCallBack(const sensor_msgs::LaserScan &ls)
00178 {
00179   if(is_first_flag_ == true)
00180   {
00181     //每扫描半圈获取一组点云数据,hokuyo激光频率按40HZ计算
00182     num_per_cloud_ = 40*motor_param_.num_of_pulse_per_circle.data/(2*motor_param_.motor_freq.data);
00183     ROS_INFO("num_per_cloud_ =%d.",num_per_cloud_);
00184     points_per_scan_ = (ls.angle_max - ls.angle_min)/ls.angle_increment;
00185     ROS_INFO("points_per_scan_ =%d.",points_per_scan_);
00186     num_points_ = points_per_scan_*num_per_cloud_;
00187                 
00188 
00189     is_first_flag_ = false;
00190 
00191     pc_data_<<num_per_cloud_<<"*"<<points_per_scan_<<"                  // DataNumber"<<"\n";
00192     pc_data_<<"0.000,0.000,0.000        // RobotPose1"<<"\n";
00193     pc_data_<<"0.000,0.000,0.000        // RobotPose2"<<"\n";
00194     pc_data_<<"0.000,0.000,0.000        // ParameterA"<<"\n";
00195     pc_data_<<"0.000,0.000,0.000        // ParameterB"<<"\n";
00196     pc_data_<<"0.000,0.000,0.000        // ParameterC"<<"\n";
00197     pc_data_<<"0.000,0.000,0.000        // ParameterD"<<"\n";
00198     pc_data_<<"0.000,0.000,0.000        // ParameterE"<<"\n";
00199     pc_data_<<"2009-1-1 0:0:0   // RecordTime"<<"\n";
00200     pc_data_<<""<<"\n";
00201     pc_data_<<"END_HEADER"<<"\n";
00202     pc_data_<<"//"<<"\n";
00203     pc_data_<<"BEGIN_3D_LASER_DATA"<<"\n";
00204   }
00205 
00206   if(is_rotate_.data == true && 
00207      ((ls.ranges[1078] > 0.21 && is_first_circle_ == true) || is_first_circle_ == false))//最后一个点到激光挡板的最大距离
00208   {
00209     is_first_circle_ = false;
00210     if(laser_seq_ >= 0 )
00211     {
00212       if(laser_seq_%num_per_cloud_ == 0)
00213       {
00214         final->points.clear();
00215         final->header.stamp = ros::Time::now();
00216         final->header.frame_id = "pch_frame";    
00217       }
00218 
00219       //laser_range_data_<<"Time stamp:"<<ls.header.stamp.toSec()<<"\n";// 激光原始数据时间戳
00220       /*publish the number of lines of the point cloud*/
00221                   
00222       ROS_INFO("angle_min:%f,angle_max:%f.",ls.angle_min,ls.angle_max);
00223       ROS_INFO("angle_increment:%f,time_increment:%f.",ls.angle_increment,ls.time_increment);
00224       ROS_INFO("range_min:%f,range_max:%f,points_per_scan_:%d.",ls.range_min,ls.range_max,points_per_scan_);
00225       ROS_INFO("The freq pulse is:%d.the num is :%d",motor_param_.motor_freq.data,motor_param_.num_of_pulse_per_circle.data);
00226 
00227       /*计算激光转过的角度start*/
00228       angle_rotated_ = laser_seq_*0.025*motor_param_.motor_freq.data*2*PAI/motor_param_.num_of_pulse_per_circle.data;
00229       /*计算激光转过的角度end*/
00230 
00231         
00232       tf::StampedTransform transform;
00233 
00234       try
00235       {
00236         odom_tf_listener_.lookupTransform("odom", "base_link", ros::Time(0), transform);
00237       }
00238       catch (tf::TransformException ex)
00239       {
00240         ROS_ERROR("%s",ex.what());
00241       }
00242 
00243       double transform_x = transform.getOrigin().x();
00244       double transform_y = transform.getOrigin().y();
00245       double transform_z = transform.getOrigin().z();
00246       double transform_th = rpyGet(transform.getRotation()).z;//获取里程计变换
00247 
00248       /*double transform_x = 0.0;
00249       double transform_y = 0.0;
00250       double transform_z = 0.0;
00251       double transform_th = 0.0;//获取里程计变换*/
00252       //double transform_rotation_x = transform.getRotation().x();
00253       //double transform_rotation_y = transform.getRotation().y();
00254       //double transform_rotation_z = transform.getRotation().z();
00255       //double transform_rotation_w = transform.getRotation().w();                      
00256 
00257       /*计算里程计原始数据时间戳start*/
00258       ros::Time now_range = ros::Time::now();
00259       double time_stamp = (now_range-time_begin_rotate_).toSec();
00260       /*计算里程计原始数据时间戳end*/
00261 
00262       laser_range_data_<<time_stamp<<" "<<angle_rotated_<<" ";//记录时间戳和云台转角
00263       odom_data_<<time_stamp<<" "<<transform_x<<" "<<transform_y<<" "<<transform_th<<"\n";
00264       
00265 
00266 
00267       for(unsigned int i = 0;i < points_per_scan_; i++)
00268       {
00269         laser_range_data_<<ls.ranges[i]<<" ";
00270         
00271         //计算激光坐标系下激光点坐标,激光坐标系下激光扫描角度为:
00272         double theta = ls.angle_min + i*ls.angle_increment;
00273         //激光坐标系下激光点坐标为:
00274         double x = ls.ranges[i]*cos(theta);
00275         double y = ls.ranges[i]*sin(theta);
00276         double z = 0;
00277 
00278         //将激光坐标系进行旋转以后为(乘以旋转矩阵R):P_ = R*P
00279         double rx = h2p_a_*x + h2p_b_*y + h2p_c_*z;
00280         double ry = h2p_d_*x + h2p_e_*y + h2p_f_*z;
00281         double rz = h2p_g_*x + h2p_h_*y + h2p_i_*z;                     
00282                                 
00283         //将激光坐标系转换为云台坐标系Pyuntai
00284         double yt_x = -ry*cos(angle_rotated_) + (rz + length_)*sin(angle_rotated_);
00285         double yt_y = -ry*sin(angle_rotated_) - (rz + length_)*cos(angle_rotated_);
00286         double yt_z = rx;
00287 
00288         //从云台坐标系转换到机器人坐标系:Probot=RZ*Pyuntai+T
00289         double x_robot = p2r_a_*yt_x + p2r_b_*yt_y + p2r_c_*yt_z + t_h2p_a_;
00290         double y_robot = p2r_d_*yt_x + p2r_e_*yt_y + p2r_f_*yt_z + t_h2p_b_;
00291         double z_robot = p2r_g_*yt_x + p2r_h_*yt_y + p2r_i_*yt_z + t_h2p_c_;
00292                                 
00293         //机器人运动过程中,还需要将点云平移后绕z轴旋转方可
00294 
00295         //先绕z轴旋转,旋转角度是机器人转角
00296         double x_end = x_robot*cos(transform_th) - y_robot*sin(transform_th);
00297         double y_end = x_robot*sin(transform_th) + y_robot*cos(transform_th);
00298         double z_end = z_robot;
00299 
00300         //再平移
00301         x_end += transform_x;
00302         y_end += transform_y;
00303         z_end += transform_z;
00304                                 
00305         pc_data_<<x_end<<" "<<y_end<<" "<<z_end<<"\n";
00306 
00307         point2_.x = x_end;
00308         point2_.y = y_end;
00309         point2_.z = z_end;
00310         //point2_.rgb = ...;//pointcloud has no colour at the present
00311         final->points.push_back(point2_); 
00312       }
00313       laser_range_data_<<"\n";
00314       //point_cloud_pub_.publish(odom_cloud_);
00315 
00316     }
00317     
00318     if((laser_seq_ + 1)%num_per_cloud_ == 0)
00319     {
00320       //publish the PointCloud2 msg
00321       point_cloud2_pub_.publish(*final);
00322     }
00323 
00324     laser_seq_++;
00325     ROS_INFO("laser_seq_=%d.",laser_seq_);
00326   }
00327 
00328 
00329 }
00330 
00331 void PointCloudOdom::odomGet(const nav_msgs::Odometry &odom)
00332 {
00333   if(is_rotate_.data == true)
00334   {
00335     //double yaw = tf::getYaw(odom.pose.pose.orientation);
00336     double yaw = rpyGet(odom.pose.pose.orientation).z;
00337     ros::Time now = ros::Time::now();
00338     double time_stamp = (now-time_begin_rotate_).toSec();
00339     //ROS_INFO("yaw = %f.",yaw);
00340     //odom_data_<<time_stamp<<" "<<odom.twist.twist.linear.x<<" "<< odom.twist.twist.angular.z<<" "<<odom.pose.pose.position.x<<" "<<odom.pose.pose.position.y<<" "<<yaw<<"\n";
00341   }
00342 }
00343 
00344 void PointCloudOdom::motorRotateStart(const std_msgs::Bool &is_run)
00345 {
00346   is_rotate_.data = is_run.data;
00347   if(is_rotate_.data == true)
00348   {
00349     time_begin_rotate_ = ros::Time::now();//电机开始转动,开始存激光数据,设个起始时间     
00350   }
00351   else
00352   {
00353     time_end_rotate_ = ros::Time::now();//电机停止转动,停止存激光数据,设个结束时间
00354   }
00355 }
00356 
00357 void PointCloudOdom::motorParamGet(const dlut_pc_odom::motor &motor_msg)
00358 {
00359   motor_param_.motor_freq.data = motor_msg.motor_freq.data;
00360   motor_param_.num_of_pulse_per_circle.data = motor_msg.num_of_pulse_per_circle.data;
00361   //time_sick_per_circle = motor_param_.num_of_pulse_per_circle.data/motor_param_.motor_freq.data;//激光每转一圈需要的时间
00362   is_first_flag_ = true;
00363 }
00364 
00365 geometry_msgs::Vector3 PointCloudOdom::rpyGet(const tf::Quaternion &qua)
00366 {
00367   double x = qua.x();
00368   double y = qua.y();
00369   double z = qua.z();
00370   double w = qua.w();
00371 
00372   geometry_msgs::Vector3 vec;
00373   vec.x = atan2(2*(w*x + y*z),1 - 2*(x*x + y*y));//from -pai to pai
00374   vec.y = asin(2*(w*y - z*x));          //from -pai/2 to pai/2
00375   vec.z = atan2(2*(w*z + x*y),1 - 2*(y*y + z*z));//from -pai to pai
00376 
00377   return vec;
00378 }
00379 
00380 geometry_msgs::Vector3 PointCloudOdom::rpyGet(const geometry_msgs::Quaternion &qua)
00381 {
00382   double x = qua.x;
00383   double y = qua.y;
00384   double z = qua.z;
00385   double w = qua.w;
00386 
00387   geometry_msgs::Vector3 vec;
00388   vec.x = atan2(2*(w*x + y*z),1 - 2*(x*x + y*y));//from -pai to pai
00389   vec.y = asin(2*(w*y - z*x));          //from -pai/2 to pai/2
00390   vec.z = atan2(2*(w*z + x*y),1 - 2*(y*y + z*z));//from -pai to pai
00391 
00392   return vec;
00393 }
00394 
00395 int main(int argc, char** argv)
00396 {
00397   ros::init(argc, argv, "odom_pch");
00398 
00399   PointCloudOdom pch;
00400 
00401   ros::spin();
00402   
00403   return 0;
00404 }


dlut_pc_odom
Author(s): Zhuang Yan , Yan Fei, Dong Bing Bing
autogenerated on Sat Jun 8 2019 19:55:41