transformMaintenance.cpp
Go to the documentation of this file.
00001 #include <math.h>
00002 #include <time.h>
00003 #include <stdio.h>
00004 #include <stdlib.h>
00005 #include <ros/ros.h>
00006 
00007 #include <nav_msgs/Odometry.h>
00008 #include <sensor_msgs/Imu.h>
00009 #include <sensor_msgs/PointCloud2.h>
00010 
00011 #include <tf/transform_datatypes.h>
00012 #include <tf/transform_broadcaster.h>
00013 
00014 #include <opencv/cv.h>
00015 #include <opencv2/highgui/highgui.hpp>
00016 
00017 #include <pcl/ros/conversions.h>
00018 #include <pcl/point_cloud.h>
00019 #include <pcl/point_types.h>
00020 #include <pcl/filters/voxel_grid.h>
00021 #include <pcl/kdtree/kdtree_flann.h>
00022 
00023 const double PI = 3.1415926;
00024 const double rad2deg = 180 / PI;
00025 const double deg2rad = PI / 180;
00026 
00027 double timeOdomBefMapped;
00028 double timeOdomAftMapped;
00029 
00030 float transformSum[6] = {0};
00031 float transformIncre[6] = {0};
00032 float transformMapped[6] = {0};
00033 float transformBefMapped[6] = {0};
00034 float transformAftMapped[6] = {0};
00035 
00036 ros::Publisher *pubLaserOdometry2Pointer = NULL;
00037 tf::TransformBroadcaster *tfBroadcaster2Pointer = NULL;
00038 nav_msgs::Odometry laserOdometry2;
00039 tf::StampedTransform laserOdometryTrans2;
00040 
00041 void transformAssociateToMap()
00042 {
00043   float x1 = cos(transformSum[2]) * (transformBefMapped[3] - transformSum[3]) 
00044            + sin(transformSum[2]) * (transformBefMapped[4] - transformSum[4]);
00045   float y1 = -sin(transformSum[2]) * (transformBefMapped[3] - transformSum[3])
00046            + cos(transformSum[2]) * (transformBefMapped[4] - transformSum[4]);
00047   float z1 = transformBefMapped[5] - transformSum[5];
00048 
00049   float x2 = x1;
00050   float y2 = cos(transformSum[0]) * y1 + sin(transformSum[0]) * z1;
00051   float z2 = -sin(transformSum[0]) * y1 + cos(transformSum[0]) * z1;
00052 
00053   transformIncre[3] = cos(transformSum[1]) * x1 - sin(transformSum[1]) * z1;
00054   transformIncre[4] = y2;
00055   transformIncre[5] = sin(transformSum[1]) * x1 + cos(transformSum[1]) * z1;
00056 
00057   transformIncre[0] = transformBefMapped[0] - transformSum[0];
00058   transformIncre[1] = transformBefMapped[1] - transformSum[1];
00059   transformIncre[2] = transformBefMapped[2] - transformSum[2];
00060 
00061   transformMapped[0] = transformAftMapped[0] - transformIncre[0];
00062   transformMapped[1] = transformAftMapped[1] - transformIncre[1];
00063   transformMapped[2] = transformAftMapped[2] - transformIncre[2];
00064 
00065   x1 = cos(transformMapped[1]) * transformIncre[3] 
00066      + sin(transformMapped[1]) * transformIncre[5];
00067   y1 = transformIncre[4];
00068   z1 = -sin(transformMapped[1]) * transformIncre[3] 
00069      + cos(transformMapped[1]) * transformIncre[5];
00070 
00071   x2 = x1;
00072   y2 = cos(transformMapped[0]) * y1 - sin(transformMapped[0]) * z1;
00073   z2 = sin(transformMapped[0]) * y1 + cos(transformMapped[0]) * z1;
00074 
00075   transformMapped[3] = transformAftMapped[3] 
00076                          - (cos(transformMapped[2]) * x2 - sin(transformMapped[2]) * y2);
00077   transformMapped[4] = transformAftMapped[4] 
00078                          - (sin(transformMapped[2]) * x2 + cos(transformMapped[2]) * y2);
00079   transformMapped[5] = transformAftMapped[5] - z2;
00080 }
00081 
00082 void laserOdometryHandler(const nav_msgs::Odometry::ConstPtr& laserOdometry)
00083 {
00084   if (fabs(timeOdomBefMapped - timeOdomAftMapped) < 0.005) {
00085 
00086     double roll, pitch, yaw;
00087     geometry_msgs::Quaternion geoQuat = laserOdometry->pose.pose.orientation;
00088     tf::Matrix3x3(tf::Quaternion(geoQuat.z, -geoQuat.x, -geoQuat.y, geoQuat.w)).getRPY(roll, pitch, yaw);
00089 
00090     transformSum[0] = -pitch;
00091     transformSum[1] = -yaw;
00092     transformSum[2] = roll;
00093 
00094     transformSum[3] = laserOdometry->pose.pose.position.x;
00095     transformSum[4] = laserOdometry->pose.pose.position.y;
00096     transformSum[5] = laserOdometry->pose.pose.position.z;
00097 
00098     transformAssociateToMap();
00099 
00100     geoQuat = tf::createQuaternionMsgFromRollPitchYaw
00101               (transformMapped[2], -transformMapped[0], -transformMapped[1]);
00102 
00103     laserOdometry2.header.stamp = laserOdometry->header.stamp;
00104     laserOdometry2.pose.pose.orientation.x = -geoQuat.y;
00105     laserOdometry2.pose.pose.orientation.y = -geoQuat.z;
00106     laserOdometry2.pose.pose.orientation.z = geoQuat.x;
00107     laserOdometry2.pose.pose.orientation.w = geoQuat.w;
00108     laserOdometry2.pose.pose.position.x = transformMapped[3];
00109     laserOdometry2.pose.pose.position.y = transformMapped[4];
00110     laserOdometry2.pose.pose.position.z = transformMapped[5];
00111     pubLaserOdometry2Pointer->publish(laserOdometry2);
00112 
00113     laserOdometryTrans2.stamp_ = laserOdometry->header.stamp;
00114     laserOdometryTrans2.setRotation(tf::Quaternion(-geoQuat.y, -geoQuat.z, geoQuat.x, geoQuat.w));
00115     laserOdometryTrans2.setOrigin(tf::Vector3(transformMapped[3], transformMapped[4], transformMapped[5]));
00116     tfBroadcaster2Pointer->sendTransform(laserOdometryTrans2);
00117   }
00118 }
00119 
00120 void odomBefMappedHandler(const nav_msgs::Odometry::ConstPtr& odomBefMapped)
00121 {
00122   timeOdomBefMapped = odomBefMapped->header.stamp.toSec();
00123 
00124   double roll, pitch, yaw;
00125   geometry_msgs::Quaternion geoQuat = odomBefMapped->pose.pose.orientation;
00126   tf::Matrix3x3(tf::Quaternion(geoQuat.z, -geoQuat.x, -geoQuat.y, geoQuat.w)).getRPY(roll, pitch, yaw);
00127 
00128   transformBefMapped[0] = -pitch;
00129   transformBefMapped[1] = -yaw;
00130   transformBefMapped[2] = roll;
00131 
00132   transformBefMapped[3] = odomBefMapped->pose.pose.position.x;
00133   transformBefMapped[4] = odomBefMapped->pose.pose.position.y;
00134   transformBefMapped[5] = odomBefMapped->pose.pose.position.z;
00135 }
00136 
00137 void odomAftMappedHandler(const nav_msgs::Odometry::ConstPtr& odomAftMapped)
00138 {
00139   timeOdomAftMapped = odomAftMapped->header.stamp.toSec();
00140 
00141   double roll, pitch, yaw;
00142   geometry_msgs::Quaternion geoQuat = odomAftMapped->pose.pose.orientation;
00143   tf::Matrix3x3(tf::Quaternion(geoQuat.z, -geoQuat.x, -geoQuat.y, geoQuat.w)).getRPY(roll, pitch, yaw);
00144 
00145   transformAftMapped[0] = -pitch;
00146   transformAftMapped[1] = -yaw;
00147   transformAftMapped[2] = roll;
00148 
00149   transformAftMapped[3] = odomAftMapped->pose.pose.position.x;
00150   transformAftMapped[4] = odomAftMapped->pose.pose.position.y;
00151   transformAftMapped[5] = odomAftMapped->pose.pose.position.z;
00152 }
00153 
00154 int main(int argc, char** argv)
00155 {
00156   ros::init(argc, argv, "transformMaintenance");
00157   ros::NodeHandle nh;
00158 
00159   ros::Subscriber subLaserOdometry = nh.subscribe<nav_msgs::Odometry> 
00160                                      ("/cam_to_init", 1, laserOdometryHandler);
00161 
00162   ros::Subscriber subOdomBefMapped = nh.subscribe<nav_msgs::Odometry> 
00163                                      ("/bef_mapped_to_init_2", 1, odomBefMappedHandler);
00164 
00165   ros::Subscriber subOdomAftMapped = nh.subscribe<nav_msgs::Odometry> 
00166                                      ("/aft_mapped_to_init_2", 1, odomAftMappedHandler);
00167 
00168   ros::Publisher pubLaserOdometry2 = nh.advertise<nav_msgs::Odometry> ("/cam_to_init_2", 1);
00169   pubLaserOdometry2Pointer = &pubLaserOdometry2;
00170   laserOdometry2.header.frame_id = "/camera_init_2";
00171   laserOdometry2.child_frame_id = "/camera";
00172 
00173   tf::TransformBroadcaster tfBroadcaster2;
00174   tfBroadcaster2Pointer = &tfBroadcaster2;
00175   laserOdometryTrans2.frame_id_ = "/camera_init_2";
00176   laserOdometryTrans2.child_frame_id_ = "/camera";
00177 
00178   ros::spin();
00179 
00180   return 0;
00181 }
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends


loam_backAndForth
Author(s): Ji Zhang
autogenerated on Sun Oct 6 2013 11:47:42