rgb_navigator.cpp
Go to the documentation of this file.
00001 
00024 #include "ccny_rgbd/apps/rgb_navigator.h"
00025 #include "aruco/aruco.h"
00026 namespace ccny_rgbd {
00027 
00028 RGBNavigator::RGBNavigator(
00029         const ros::NodeHandle& nh,
00030         const ros::NodeHandle& nh_private):
00031     nh_(nh),
00032     nh_private_(nh_private),
00033     rgbd_frame_index_(0)
00034 {
00035     ROS_INFO("Starting RGBNavigator node");
00036 
00037     // **** params
00038 
00039     initParams();
00040 
00041     // **** publishers
00042 
00043     keyframes_pub_ = nh_.advertise<PointCloudT>(
00044                 "keyframes", queue_size_);
00045     poses_pub_ = nh_.advertise<visualization_msgs::Marker>(
00046                 "keyframe_poses", queue_size_);
00047     kf_assoc_pub_ = nh_.advertise<visualization_msgs::Marker>(
00048                 "keyframe_associations", queue_size_);
00049     path_pub_ = nh_.advertise<PathMsg>(
00050                 "mapper_path", queue_size_);
00051 
00052     // **** services
00053 
00054     pub_keyframe_service_ = nh_.advertiseService(
00055                 "publish_keyframe", &RGBNavigator::publishKeyframeSrvCallback, this);
00056     pub_keyframes_service_ = nh_.advertiseService(
00057                 "publish_keyframes", &RGBNavigator::publishKeyframesSrvCallback, this);
00058     save_kf_service_ = nh_.advertiseService(
00059                 "save_keyframes", &RGBNavigator::saveKeyframesSrvCallback, this);
00060     load_kf_service_ = nh_.advertiseService(
00061                 "load_keyframes", &RGBNavigator::loadKeyframesSrvCallback, this);
00062     save_pcd_map_service_ = nh_.advertiseService(
00063                 "save_pcd_map", &RGBNavigator::savePcdMapSrvCallback, this);
00064     save_octomap_service_ = nh_.advertiseService(
00065                 "save_octomap", &RGBNavigator::saveOctomapSrvCallback, this);
00066     add_manual_keyframe_service_ = nh_.advertiseService(
00067                 "add_manual_keyframe", &RGBNavigator::addManualKeyframeSrvCallback, this);
00068     generate_graph_service_ = nh_.advertiseService(
00069                 "generate_graph", &RGBNavigator::generateGraphSrvCallback, this);
00070     solve_graph_service_ = nh_.advertiseService(
00071                 "solve_graph", &RGBNavigator::solveGraphSrvCallback, this);
00072 
00073     // **** subscribers
00074 
00075     ImageTransport rgb_it(nh_);
00076     //    ImageTransport depth_it(nh_);
00077 
00078     sub_rgb_.subscribe(rgb_it,     "/camera/rgb/image_rect_color",   queue_size_);
00079     //    sub_depth_.subscribe(depth_it, "/camera/depth_registered/image_rect_raw", queue_size_);
00080     sub_info_.subscribe(nh_,       "/camera/rgb/camera_info",  queue_size_);
00081 
00082     // Synchronize inputs.
00083     sync_.reset(new RGBSynchronizer(
00084                     RGBSyncPolicy(queue_size_), sub_rgb_, sub_info_));
00085 
00086     sync_->registerCallback(boost::bind(&RGBNavigator::RGBCallback, this, _1, _2));
00087 }
00088 
00089 RGBNavigator::~RGBNavigator()
00090 {
00091 
00092 }
00093 aruco::MarkerDetector MDetector;
00094 rgbdtools::KeyframeGraphSolverISAM solver_;
00095 void RGBNavigator::initParams()
00096 {
00097     bool verbose;
00098 
00099     if (!nh_private_.getParam ("verbose", verbose))
00100         verbose = true;
00101     if (!nh_private_.getParam ("queue_size", queue_size_))
00102         queue_size_ = 5;
00103     if (!nh_private_.getParam ("fixed_frame", fixed_frame_))
00104         fixed_frame_ = "/odom";
00105     if (!nh_private_.getParam ("pcd_map_res", pcd_map_res_))
00106         pcd_map_res_ = 0.01;
00107     if (!nh_private_.getParam ("octomap_res", octomap_res_))
00108         octomap_res_ = 0.05;
00109     if (!nh_private_.getParam ("octomap_with_color", octomap_with_color_))
00110         octomap_with_color_ = true;
00111     if (!nh_private_.getParam ("kf_dist_eps", kf_dist_eps_))
00112         kf_dist_eps_  = 0.10;
00113     if (!nh_private_.getParam ("kf_angle_eps", kf_angle_eps_))
00114         kf_angle_eps_  = 10.0 * M_PI / 180.0;
00115     if (!nh_private_.getParam ("max_range", max_range_))
00116         max_range_  = 10.0;
00117     if (!nh_private_.getParam ("max_stdev", max_stdev_))
00118         max_stdev_  = 555;
00119     if (!nh_private_.getParam ("max_map_z", max_map_z_))
00120         max_map_z_ = std::numeric_limits<double>::infinity();
00121 
00122     // configure graph detection
00123     MDetector.setThresholdParams( 10.0,7.0);
00124     MDetector.setCornerRefinementMethod(aruco::MarkerDetector::LINES);
00125 
00126     int graph_n_keypoints;
00127     int graph_n_candidates;
00128     int graph_k_nearest_neighbors;
00129     bool graph_matcher_use_desc_ratio_test = true;
00130 
00131     if (!nh_private_.getParam ("graph/n_keypoints", graph_n_keypoints))
00132         graph_n_keypoints = 500;
00133     if (!nh_private_.getParam ("graph/n_candidates", graph_n_candidates))
00134         graph_n_candidates = 10;
00135     if (!nh_private_.getParam ("graph/k_nearest_neighbors", graph_k_nearest_neighbors))
00136         graph_k_nearest_neighbors = 4;
00137     int min_inliers = 25;
00138 
00139     graph_detector_.setNKeypoints(graph_n_keypoints);
00140     graph_detector_.setNCandidates(graph_n_candidates);
00141     graph_detector_.setKNearestNeighbors(graph_k_nearest_neighbors);
00142     graph_detector_.setMatcherUseDescRatioTest(graph_matcher_use_desc_ratio_test);
00143     graph_detector_.setSacMinInliers(min_inliers);
00144     graph_detector_.setSACReestimateTf(false);
00145     graph_detector_.setSACSaveResults(true);
00146     graph_detector_.setVerbose(verbose);
00147     graph_detector_.setMaxIterations(300);
00148 }
00149 
00150 void RGBNavigator::filter_aruco()
00151 {
00152     double max_dist = 0.2+0.2+0.2;
00153     std::vector<std::vector<double> > positions;
00154     std::vector<std::vector<int> > inds;
00155     for(u_int i = 0; i < aruco_pos.size(); i++)
00156     {
00157         std::vector<double> val;
00158         val.push_back(0);
00159         val.push_back(0);
00160         val.push_back(0);
00161         std::vector<int> sub_inds;
00162         for(u_int j = 0; j < aruco_pos.size() ; j++)
00163         {
00164             double man_dist = std::abs(aruco_pos[i][0]-aruco_pos[j][0])+ std::abs(aruco_pos[i][1]-aruco_pos[j][1])+ std::abs(aruco_pos[i][2]-aruco_pos[j][2]);
00165             if (man_dist < max_dist)
00166             {
00167                 sub_inds.push_back(j);
00168                 val[0] += aruco_pos[j][0];
00169                 val[1] += aruco_pos[j][1];
00170                 val[2] += aruco_pos[j][2];
00171             }
00172 
00173         }
00174         val[0] /= sub_inds.size();
00175         val[1] /= sub_inds.size();
00176         val[2] /= sub_inds.size();
00177         positions.push_back(val);
00178         inds.push_back(sub_inds);
00179     }
00180     PathMsg ar;
00181     ar.header.frame_id = fixed_frame_;
00182     ar.header.seq = 0;
00183     ar.header.stamp = ros::Time::now();
00184     std::vector<std::vector<double> > aruc;
00185     //    aruco_pos.clear();
00186     for(u_int i = 0; i < positions.size(); i++)
00187     {
00188         std::vector<double> val;
00189         val.push_back(0);
00190         val.push_back(0);
00191         val.push_back(0);
00192         std::vector<int> sub_inds;
00193         for(u_int j = 0; j < positions.size() ; j++)
00194         {
00195             if(inds[j].size() < 4) //we need min 3 readings to consider a position safe.
00196             {
00197                 continue;
00198             }
00199             double man_dist = std::abs(positions[i][0]-positions[j][0])+ std::abs(positions[i][1]-positions[j][1])+ std::abs(positions[i][2]-positions[j][2]);
00200             if (man_dist < max_dist)
00201             {
00202                 sub_inds.push_back(j);
00203                 val[0] += positions[j][0];
00204                 val[1] += positions[j][1];
00205                 val[2] += positions[j][2];
00206             }
00207 
00208         }
00209         if(sub_inds.size() < 4)
00210         {
00211             val[0] = -99999;
00212             aruc.push_back(val);
00213             continue;
00214         }
00215         if(!(val[0]==-99999))
00216         {
00217             val[0] /= sub_inds.size();
00218             val[1] /= sub_inds.size();
00219             val[2] /= sub_inds.size();
00220         }
00221         aruc.push_back(val);
00222     }
00223     aruco_pos.clear();
00224     for(u_int i = 0; i< aruc.size(); i++)
00225     {
00226         geometry_msgs::PoseStamped pose;
00227         if(aruc[i][0] == -99999)
00228             continue;
00229         rgbdtools::RGBDKeyframe keyframe=keyframes_[aruco_kfs[i]];
00230         pose.header.frame_id = fixed_frame_;
00231         pose.header.seq = keyframe.header.seq;
00232         pose.header.stamp.sec = keyframe.header.stamp.sec;
00233         pose.header.stamp.nsec = keyframe.header.stamp.nsec;
00234         pose.pose.position.x = aruc[i][0];
00235         pose.pose.position.y = aruc[i][1];
00236         pose.pose.position.z = aruc[i][2];
00237         pose.pose.orientation.x = 1;
00238         pose.pose.orientation.y = 0;
00239         pose.pose.orientation.z = 0;
00240         pose.pose.orientation.w = 1;
00241         ar.poses.push_back(pose);
00242         std::vector<double> pos;
00243         pos.push_back(aruc[i][0]);
00244         pos.push_back(aruc[i][1]);
00245         pos.push_back(aruc[i][2]);
00246         aruco_pos.push_back(pos);
00247     }
00248     path_pub_.publish(ar);
00249     //    positions.clear();
00250     //    for(u_int i = 0; i< aruco_pos.size(); i++)
00251     //    {
00252     //        double x,y,z;
00253     //        x = aruco_pos[i][0];
00254     //        y = aruco_pos[i][1];
00255     //        z = aruco_pos[i][2];
00256     //        bool hit = false;
00257     //        for(u_int j = 0; j < positions.size(); j++)
00258     //        {
00259     //            if (x == positions[j][0] && y == positions[j][1] && z == positions[j][2])
00260     //            {
00261     //                hit = true;
00262     //                break;
00263     //            }
00264     //        }
00265     //        if(!hit)
00266     //        {
00267     //            positions.push_back(aruco_pos[i]);
00268     //        }
00269     //    }
00270     //    aruco_pos.clear();
00271     //    for(u_int i = 0; i < positions.size(); i++)
00272     //        aruco_pos.push_back(positions[i]);
00273     //    std::cout << "oh hai!" << std::endl;
00274 }
00275 
00276 bool first = true;
00277 aruco::CameraParameters param;
00278 cv::Mat intr, dist;
00279 cv::Size CamSize;
00280 
00281 void RGBNavigator::RGBCallback(
00282         const ImageMsg::ConstPtr& rgb_msg,
00283         const CameraInfoMsg::ConstPtr& info_msg)
00284 {
00285     tf::StampedTransform transform;
00286     transform.setIdentity();
00287     if(keyframes_.size() == 0)
00288     {
00289         std::cout << "Map not loaded yet" << std::endl;
00290         return;
00291     }
00292     //    const ros::Time& time = rgb_msg->header.stamp;
00293     if (first)
00294     {
00295         convertCameraInfoToMats(info_msg, intr, dist);
00296         CamSize.width = info_msg->width;
00297         CamSize.height = info_msg->height;
00298         param.CameraMatrix = intr;
00299         param.CamSize = CamSize;
00300         param.Distorsion = dist;
00301 
00302         first = false;
00303     }
00304     //    try{
00305     //        tf_listener_.waitForTransform(
00306     //                    fixed_frame_, rgb_msg->header.frame_id, time, ros::Duration(0.1));
00307     //        tf_listener_.lookupTransform(
00308     //                    fixed_frame_, rgb_msg->header.frame_id, time, transform);
00309     //    }
00310     //    catch(...)
00311     //    {
00312     //        return;
00313     //    }
00314     cv_bridge::CvImage out_msg;
00315     out_msg.header   = rgb_msg->header; // Same timestamp and tf frame as input image
00316     out_msg.encoding = sensor_msgs::image_encodings::TYPE_16UC1; // depth enc
00317     out_msg.image    = cv::Mat::zeros(rgb_msg->height,rgb_msg->width, CV_8UC1); // Your cv::Mat
00318     ImageMsg::Ptr depth_msg =  out_msg.toImageMsg();
00319     // create a new frame and increment the counter
00320     rgbdtools::RGBDFrame frame;
00321     createRGBDFrameFromROSMessages(rgb_msg,depth_msg, info_msg, frame);
00322     frame.index = rgbd_frame_index_;
00323     rgbd_frame_index_++;
00324     //    std::vector<aruco::Marker> markers;
00325 
00326 
00327     //    MDetector.detect(frame.rgb_img,markers,param,0.20); // magic number 0.20 = marker size
00328     //    if (markers.size()>0)
00329     //    {
00330     //        manual_add_ = true;
00331     //        solver_.giveMarkers(markers);
00332     //    }
00333     addKeyframe(frame, keyframes_[keyframes_.size()-1].pose);
00334 
00335     graph_detector_.prepareFeaturesForRANSAC_Iterative(keyframes_.size()-1,keyframes_);
00336     graph_detector_.buildMatchMatrixSurfTree_Iterative(keyframes_.size()-1,keyframes_);
00337     graph_detector_.buildCandidateMatrixSurfTree_Iterative(keyframes_.size()-1);
00338     graph_detector_.buildCorrespondenceMatrix_rgb_Iterative(keyframes_.size()-1,keyframes_,associations_);
00339 
00340     solver_.add_edges(keyframes_.size()-1,keyframes_,associations_);
00341     solver_.solve_rgb_Iterative(keyframes_);
00342 
00343 
00344     publishKeyframePoses();
00345     publishPath();
00346     publishKeyframeAssociations();
00347 }
00348 
00349 int triple_add=0;
00350 
00351 
00352 bool RGBNavigator::processFrame(
00353         const rgbdtools::RGBDFrame& frame,
00354         const AffineTransform& pose)
00355 {
00356     // add the frame pose to the path vector
00357     geometry_msgs::PoseStamped frame_pose;
00358     tf::Transform frame_tf = tfFromEigenAffine(pose);
00359     tf::poseTFToMsg(frame_tf, frame_pose.pose);
00360 
00361     // update the header of the pose for the path
00362     frame_pose.header.frame_id = fixed_frame_;
00363     frame_pose.header.seq = frame.header.seq;
00364     frame_pose.header.stamp.sec = frame.header.stamp.sec;
00365     frame_pose.header.stamp.nsec = frame.header.stamp.nsec;
00366 
00367     path_msg_.poses.push_back(frame_pose);
00368 
00369     // determine if a new keyframe is needed
00370     bool result;
00371 
00372     if(keyframes_.empty() || manual_add_)
00373     {
00374         result = true;
00375     }
00376     else
00377     {
00378         double dist, angle;
00379         getTfDifference(tfFromEigenAffine(pose),
00380                         tfFromEigenAffine(keyframes_.back().pose),
00381                         dist, angle);
00382 
00383         if (triple_add >0 || dist > kf_dist_eps_ || angle > kf_angle_eps_)
00384         {
00385             result = true;
00386             //        if (triple_add == 0)
00387             //        {
00388             //            triple_add = 2;
00389             //        }
00390             //        else
00391             //        {
00392             //            triple_add--;
00393             //        }
00394         }
00395         else
00396             result = false;
00397     }
00398 
00399     if (result)
00400     {
00401         addKeyframe(frame, pose);
00402     }
00403     return result;
00404 }
00405 
00406 void RGBNavigator::addKeyframe(
00407         const rgbdtools::RGBDFrame& frame,
00408         const AffineTransform& pose)
00409 {
00410     rgbdtools::RGBDKeyframe keyframe(frame);
00411     keyframe.pose = pose;
00412 
00413     if (manual_add_)
00414     {
00415         ROS_INFO("Adding frame manually");
00416         manual_add_ = false;
00417         keyframe.manually_added = true;
00418     }
00419     keyframes_.push_back(keyframe);
00420 }
00421 
00422 bool RGBNavigator::publishKeyframeSrvCallback(
00423         PublishKeyframe::Request& request,
00424         PublishKeyframe::Response& response)
00425 {
00426     int kf_idx = request.id;
00427 
00428     if (kf_idx >= 0 && kf_idx < (int)keyframes_.size())
00429     {
00430         ROS_INFO("Publishing keyframe %d", kf_idx);
00431         publishKeyframeData(kf_idx);
00432         Pose(kf_idx);
00433         return true;
00434     }
00435     else
00436     {
00437         ROS_ERROR("Index out of range");
00438         return false;
00439     }
00440 }
00441 
00442 bool RGBNavigator::publishKeyframesSrvCallback(
00443         PublishKeyframes::Request& request,
00444         PublishKeyframes::Response& response)
00445 {
00446     bool found_match = false;
00447 
00448     // regex matching - try match the request string against each
00449     // keyframe index
00450     boost::regex expression(request.re);
00451 
00452     for (unsigned int kf_idx = 0; kf_idx < keyframes_.size(); ++kf_idx)
00453     {
00454         std::stringstream ss;
00455         ss << kf_idx;
00456         std::string kf_idx_string = ss.str();
00457 
00458         boost::smatch match;
00459 
00460         if(boost::regex_match(kf_idx_string, match, expression))
00461         {
00462             found_match = true;
00463             ROS_INFO("Publishing keyframe %d", kf_idx);
00464             publishKeyframeData(kf_idx);
00465             publishKeyframePose(kf_idx);
00466             usleep(25000);
00467         }
00468     }
00469 
00470     publishPath();
00471 
00472     return found_match;
00473 }
00474 
00475 void RGBNavigator::publishKeyframeData(int i)
00476 {
00477     //    //for testing iterative stuff
00478     //    graph_detector_.prepareFeaturesForRANSAC_Iterative(i,keyframes_);
00479     //    graph_detector_.buildMatchMatrixSurfTree_Iterative(i,keyframes_);
00480     //    graph_detector_.buildCandidateMatrixSurfTree_Iterative(i);
00481     rgbdtools::RGBDKeyframe& keyframe = keyframes_[i];
00482 
00483     // construct a cloud from the images
00484     PointCloudT cloud;
00485     keyframe.constructDensePointCloud(cloud, max_range_, max_stdev_);
00486 
00487     // cloud transformed to the fixed frame
00488     PointCloudT cloud_ff;
00489     pcl::transformPointCloud(cloud, cloud_ff, keyframe.pose);
00490 
00491     cloud_ff.header.frame_id = fixed_frame_;
00492 
00493     keyframes_pub_.publish(cloud_ff);
00494 }
00495 
00496 void RGBNavigator::publishKeyframeAssociations()
00497 {
00498     visualization_msgs::Marker marker;
00499     marker.header.stamp = ros::Time::now();
00500     marker.header.frame_id = fixed_frame_;
00501     marker.id = 0;
00502     marker.type = visualization_msgs::Marker::LINE_LIST;
00503     marker.action = visualization_msgs::Marker::ADD;
00504 
00505     marker.points.resize(associations_.size() * 2);
00506 
00507     marker.color.a = 1.0;
00508 
00509     for (unsigned int as_idx = 0; as_idx < associations_.size(); ++as_idx)
00510     {
00511         // set up shortcut references
00512         const rgbdtools::KeyframeAssociation& association = associations_[as_idx];
00513         int kf_idx_a = association.kf_idx_a;
00514         int kf_idx_b = association.kf_idx_b;
00515         rgbdtools::RGBDKeyframe& keyframe_a = keyframes_[kf_idx_a];
00516         rgbdtools::RGBDKeyframe& keyframe_b = keyframes_[kf_idx_b];
00517 
00518         int idx_start = as_idx*2;
00519         int idx_end   = as_idx*2 + 1;
00520 
00521         tf::Transform keyframe_a_pose = tfFromEigenAffine(keyframe_a.pose);
00522         tf::Transform keyframe_b_pose = tfFromEigenAffine(keyframe_b.pose);
00523 
00524         // start point for the edge
00525         marker.points[idx_start].x = keyframe_a_pose.getOrigin().getX();
00526         marker.points[idx_start].y = keyframe_a_pose.getOrigin().getY();
00527         marker.points[idx_start].z = keyframe_a_pose.getOrigin().getZ();
00528 
00529         // end point for the edge
00530         marker.points[idx_end].x = keyframe_b_pose.getOrigin().getX();
00531         marker.points[idx_end].y = keyframe_b_pose.getOrigin().getY();
00532         marker.points[idx_end].z = keyframe_b_pose.getOrigin().getZ();
00533 
00534         if (association.type == rgbdtools::KeyframeAssociation::VO)
00535         {
00536             marker.ns = "VO";
00537             marker.scale.x = 0.002;
00538 
00539             marker.color.r = 0.0;
00540             marker.color.g = 1.0;
00541             marker.color.b = 0.0;
00542         }
00543         else if (association.type == rgbdtools::KeyframeAssociation::RANSAC)
00544         {
00545             marker.ns = "RANSAC";
00546             marker.scale.x = 0.002;
00547 
00548             marker.color.r = 1.0;
00549             marker.color.g = 1.0;
00550             marker.color.b = 0.0;
00551         }
00552 
00553         kf_assoc_pub_.publish(marker);
00554     }
00555 }
00556 
00557 void RGBNavigator::publishKeyframePoses()
00558 {
00559     for(unsigned int kf_idx = 0; kf_idx < keyframes_.size(); ++kf_idx)
00560     {
00561         publishKeyframePose(kf_idx);
00562     }
00563 }
00564 
00565 void RGBNavigator::publishArucoPos()
00566 {
00567     for(u_int i = 0; i < aruco_pos.size(); i++)
00568     {
00569         visualization_msgs::Marker marker;
00570         marker.header.stamp = ros::Time::now();
00571         marker.header.frame_id = fixed_frame_;
00572         marker.ns = "Aruco_pos";
00573         marker.id = i;
00574         marker.type = visualization_msgs::Marker::SPHERE;
00575         marker.action = visualization_msgs::Marker::ADD;
00576         marker.pose.position.x = aruco_pos[i][0];
00577         marker.pose.position.y = aruco_pos[i][1];
00578         marker.pose.position.z = aruco_pos[i][2];
00579         marker.pose.orientation.x = 0.0;
00580         marker.pose.orientation.y = 0.0;
00581         marker.pose.orientation.z = 0.0;
00582         marker.pose.orientation.w = 1.0;
00583         marker.scale.x = 0.1;
00584         marker.scale.y = 0.1;
00585         marker.scale.z = 0.1;
00586         marker.color.a = 1.0;
00587         marker.color.r = 1.0;
00588         marker.color.g = 0.0;
00589         marker.color.b = 0.0;
00590         poses_pub_.publish(marker);
00591     }
00592 }
00593 
00594 void RGBNavigator::publishKeyframePose(int i)
00595 {
00596     rgbdtools::RGBDKeyframe& keyframe = keyframes_[i];
00597     if(!keyframe.used && (u_int)i >= solver_.n_original_poses )
00598         return;
00599     // **** publish camera pose
00600 
00601     visualization_msgs::Marker marker;
00602     marker.header.stamp = ros::Time::now();
00603     marker.header.frame_id = fixed_frame_;
00604     marker.ns = "keyframe_poses";
00605     marker.id = i;
00606     marker.type = visualization_msgs::Marker::ARROW;
00607     marker.action = visualization_msgs::Marker::ADD;
00608     marker.points.resize(2);
00609 
00610     // start point for the arrow
00611     tf::Transform keyframe_pose = tfFromEigenAffine(keyframe.pose);
00612     marker.points[0].x = keyframe_pose.getOrigin().getX();
00613     marker.points[0].y = keyframe_pose.getOrigin().getY();
00614     marker.points[0].z = keyframe_pose.getOrigin().getZ();
00615 
00616     // end point for the arrow
00617     tf::Transform ep;
00618     ep.setIdentity();
00619     ep.setOrigin(tf::Vector3(0.00, 0.00, 0.12)); // z = arrow length
00620     ep = keyframe_pose * ep;
00621 
00622     marker.points[1].x = ep.getOrigin().getX();
00623     marker.points[1].y = ep.getOrigin().getY();
00624     marker.points[1].z = ep.getOrigin().getZ();
00625 
00626     marker.scale.x = 0.02; // shaft radius
00627     marker.scale.y = 0.05; // head radius
00628     if((u_int)i < solver_.n_original_poses)
00629     {
00630         marker.color.a = 1.0;
00631         marker.color.r = 0.0;
00632         marker.color.g = 1.0;
00633         marker.color.b = 0.0;
00634     }
00635     else
00636     {
00637 
00638 
00639         marker.color.a = 1.0;
00640         marker.color.r = 1.0;
00641         marker.color.g = 1.0;
00642         marker.color.b = 0.0;
00643 
00644 
00645     }
00646     poses_pub_.publish(marker);
00647 
00648     // **** publish frame index text
00649 
00650     visualization_msgs::Marker marker_text;
00651     marker_text.header.stamp = ros::Time::now();
00652     marker_text.header.frame_id = fixed_frame_;
00653     marker_text.ns = "keyframe_indexes";
00654     marker_text.id = i;
00655     marker_text.type = visualization_msgs::Marker::TEXT_VIEW_FACING;
00656     marker_text.action = visualization_msgs::Marker::ADD;
00657 
00658     tf::poseTFToMsg(keyframe_pose, marker_text.pose);
00659 
00660     marker_text.pose.position.z -= 0.05;
00661 
00662     char label[6];
00663     sprintf(label, "%d", i);
00664     marker_text.text = label;
00665 
00666     marker_text.color.a = 1.0;
00667     marker_text.color.r = 1.0;
00668     marker_text.color.g = 1.0;
00669     marker_text.color.b = 0.0;
00670 
00671     marker_text.scale.z = 0.05; // shaft radius
00672 
00673     poses_pub_.publish(marker_text);
00674 }
00675 
00676 bool RGBNavigator::saveKeyframesSrvCallback(
00677         Save::Request& request,
00678         Save::Response& response)
00679 {
00680     std::string filepath = request.filename;
00681 
00682     ROS_INFO("Saving keyframes...");
00683     std::string filepath_keyframes = filepath + "/keyframes/";
00684     bool result_kf = saveKeyframes(keyframes_, filepath_keyframes);
00685     if (result_kf) ROS_INFO("Keyframes saved to %s", filepath.c_str());
00686     else ROS_ERROR("Keyframe saving failed!");
00687 
00688     ROS_INFO("Saving path...");
00689     bool result_path = savePath(filepath);
00690     savePathTUMFormat(filepath);
00691     if (result_path ) ROS_INFO("Path saved to %s", filepath.c_str());
00692     else ROS_ERROR("Path saving failed!");
00693     solver_.save_graph(filepath);
00694 
00695     return result_kf && result_path;
00696 }
00697 
00698 bool RGBNavigator::loadKeyframesSrvCallback(
00699         Load::Request& request,
00700         Load::Response& response)
00701 {
00702     bool skip = false;
00703     ros::WallTime start_all = ros::WallTime::now();
00704     std::string filepath1 = request.filename;
00705     char buffer[200];
00706     std::string filepath;
00707     if(filepath1.at(filepath1.size()-1)=='!')
00708     {
00709         skip = true;
00710         int copied = filepath1.copy(buffer,filepath1.size()-1,0);
00711         buffer[copied] = '\0';
00712         filepath = buffer;
00713     }
00714     else
00715     {
00716         filepath = filepath1;
00717     }
00718     ROS_INFO("Loading keyframes...");
00719     std::string filepath_keyframes = filepath + "/keyframes/";
00720     bool result_kf = loadKeyframes(keyframes_, filepath_keyframes);
00721     if (result_kf) ROS_INFO("Keyframes loaded successfully");
00722     else ROS_ERROR("Keyframe loading failed!");
00723 
00724     ROS_INFO("Loading path...");
00725     bool result_path = loadPath(filepath);
00726     if (result_path) ROS_INFO("Path loaded successfully");
00727     else ROS_ERROR("Path loading failed!");
00728     publishKeyframePoses();
00729     solver_.parse((filepath).c_str(),keyframes_);
00730     publishKeyframePoses();
00731     if(!(result_kf && result_path))
00732         return false;
00733     if(skip)
00734         return result_kf && result_path;
00735     graph_detector_.generateKeyframeAssociations_Iterative(keyframes_,associations_);
00736     double dur = getMsDuration(start_all);
00737 
00738     ROS_INFO("Everything took %.1f ms", dur);
00739     return result_kf && result_path;
00740 }
00741 
00742 bool RGBNavigator::savePcdMapSrvCallback(
00743         Save::Request& request,
00744         Save::Response& response)
00745 {
00746     ROS_INFO("Saving map as pcd...");
00747     const std::string& path = request.filename;
00748     bool result = savePcdMap(path);
00749 
00750     if (result) ROS_INFO("Pcd map saved to %s", path.c_str());
00751     else ROS_ERROR("Pcd map saving failed");
00752 
00753     return result;
00754 }
00755 
00756 bool RGBNavigator::saveOctomapSrvCallback(
00757         Save::Request& request,
00758         Save::Response& response)
00759 {
00760     ROS_INFO("Saving map as Octomap...");
00761     const std::string& path = request.filename;
00762     bool result = saveOctomap(path);
00763 
00764     if (result) ROS_INFO("Octomap saved to %s", path.c_str());
00765     else ROS_ERROR("Octomap saving failed");
00766 
00767     return result;
00768 }
00769 
00770 //void RGBNavigator::createmap(octomap::ColorOcTree* m_octree)
00771 //{
00772 //    nav_msgs::OccupancyGrid m_gridmap;
00773 //    m_gridmap.data.clear();
00774 //    m_gridmap.info.height = 0.0;
00775 //    m_gridmap.info.width = 0.0;
00776 //    m_gridmap.info.resolution = 0.0;
00777 //    m_gridmap.info.origin.position.x = 0.0;
00778 //    m_gridmap.info.origin.position.y = 0.0;
00779 //    m_gridmap.header.frame_id = fixed_frame_;
00780 //    m_gridmap.header.stamp = ros::Time::now();
00781 //    // now, traverse all leafs in the tree:
00782 //    for (octomap::ColorOcTree::iterator it = m_octree->begin(999),
00783 //         end = m_octree->end(); it != end; ++it)
00784 //    {
00785 //        if (m_octree->isNodeOccupied(*it)){
00786 //            double z = it.getZ();
00787 //            if (z > min_map_z_ && z < max_map_z_)
00788 //            {
00789 //                double size = it.getSize();
00790 //                double x = it.getX();
00791 //                double y = it.getY();
00792 
00793 
00794 //                if (publishCollisionMap){
00795 //                    collObjBox.extents.x = collObjBox.extents.y = collObjBox.extents.z = size;
00796 
00797 //                    collObjBox.center.x = x;
00798 //                    collObjBox.center.y = y;
00799 //                    collObjBox.center.z = z;
00800 //                    collisionMap.boxes.push_back(collObjBox);
00801 
00802 //                }
00803 
00804 //                //create marker:
00805 //                if (publishMarkerArray){
00806 //                    unsigned idx = it.getDepth();
00807 //                    assert(idx < occupiedNodesVis.markers.size());
00808 
00809 //                    geometry_msgs::Point cubeCenter;
00810 //                    cubeCenter.x = x;
00811 //                    cubeCenter.y = y;
00812 //                    cubeCenter.z = z;
00813 
00814 //                    occupiedNodesVis.markers[idx].points.push_back(cubeCenter);
00815 //                    if (m_useHeightMap){
00816 //                        double minX, minY, minZ, maxX, maxY, maxZ;
00817 //                        m_octree->getMetricMin(minX, minY, minZ);
00818 //                        m_octree->getMetricMax(maxX, maxY, maxZ);
00819 
00820 //                        double h = (1.0 - std::min(std::max((cubeCenter.z-minZ)/ (maxZ - minZ), 0.0), 1.0)) *m_colorFactor;
00821 //                        occupiedNodesVis.markers[idx].colors.push_back(heightMapColor(h));
00822 //                    }
00823 //                }
00824 
00825 //                // insert into pointcloud:
00826 //                if (publishPointCloud)
00827 //                    pclCloud.push_back(pcl::PointXYZ(x, y, z));
00828 
00829 //            }
00830 //        } else{ // node not occupied => mark as free in 2D map if unknown so far
00831 //            double z = it.getZ();
00832 //            if (z > m_occupancyMinZ && z < m_occupancyMaxZ)
00833 //            {
00834 //                handleFreeNode(it);
00835 //                if (inUpdateBBX)
00836 //                    handleFreeNodeInBBX(it);
00837 
00838 //                if (m_publishFreeSpace){
00839 //                    double x = it.getX();
00840 //                    double y = it.getY();
00841 
00842 //                    if (publishFreeMap){
00843 //                        freeObjBox.extents.x = freeObjBox.extents.y = freeObjBox.extents.z = it.getSize();
00844 //                        freeObjBox.center.x = x;
00845 //                        freeObjBox.center.y = y;
00846 //                        freeObjBox.center.z = z;
00847 //                        freeMap.boxes.push_back(freeObjBox);
00848 //                    }
00849 
00850 //                    //create marker for free space:
00851 //                    if (publishFreeMarkerArray){
00852 //                        unsigned idx = it.getDepth();
00853 //                        assert(idx < freeNodesVis.markers.size());
00854 
00855 //                        geometry_msgs::Point cubeCenter;
00856 //                        cubeCenter.x = x;
00857 //                        cubeCenter.y = y;
00858 //                        cubeCenter.z = z;
00859 
00860 //                        freeNodesVis.markers[idx].points.push_back(cubeCenter);
00861 //                    }
00862 //                }
00863 
00864 //            }
00865 //        }
00866 //    }
00867 //}
00868 
00869 bool RGBNavigator::addManualKeyframeSrvCallback(
00870         AddManualKeyframe::Request& request,
00871         AddManualKeyframe::Response& response)
00872 {
00873 
00874     manual_add_ = true;
00875 
00876     return true;
00877 }
00878 
00879 bool RGBNavigator::generateGraphSrvCallback(
00880         GenerateGraph::Request& request,
00881         GenerateGraph::Response& response)
00882 {
00883     associations_.clear();
00884     graph_detector_.generateKeyframeAssociations(keyframes_, associations_);
00885 
00886     ROS_INFO("%d associations detected", (int)associations_.size());
00887     publishKeyframePoses();
00888     publishKeyframeAssociations();
00889 
00890     return true;
00891 }
00892 
00893 bool RGBNavigator::solveGraphSrvCallback(
00894         SolveGraph::Request& request,
00895         SolveGraph::Response& response)
00896 {
00897     ros::WallTime start = ros::WallTime::now();
00898 
00899     // Graph solving: keyframe positions only, path is interpolated
00900     //  graph_solver_.solve(keyframes_, associations_);
00901     solver_.optimizeGraph();
00902     //  updatePathFromKeyframePoses();
00903     max_map_z_ = getmaxheight(path_msg_)+0.2; //cut the ceiling
00904     min_map_z_= getminheight(path_msg_)-0.5; //cut the ground
00905     // Graph solving: keyframe positions and VO path
00906     /*
00907   AffineTransformVector path;
00908   pathROSToEigenAffine(path_msg_, path);
00909   graph_solver_.solve(keyframes_, associations_, path);
00910   pathEigenAffineToROS(path, path_msg_);
00911   */
00912 
00913     double dur = getMsDuration(start);
00914 
00915     ROS_INFO("Solving took %.1f ms", dur);
00916 
00917     //  publishPath();
00918     publishKeyframePoses();
00919     publishKeyframeAssociations();
00920 
00921     return true;
00922 }
00923 
00924 
00928 void RGBNavigator::updatePathFromKeyframePoses()
00929 {
00930     int kf_size = keyframes_.size();
00931     int f_size = path_msg_.poses.size();
00932 
00933     // temporary store the new path
00934     AffineTransformVector path_new;
00935     path_new.resize(f_size);
00936 
00937     if (kf_size < 2) return;
00938 
00939     for (int kf_idx = 0; kf_idx < kf_size - 1; ++kf_idx)
00940     {
00941         // the indices of the current and next keyframes (a and b)
00942         const rgbdtools::RGBDKeyframe& keyframe_a = keyframes_[kf_idx];
00943         const rgbdtools::RGBDKeyframe& keyframe_b = keyframes_[kf_idx + 1];
00944 
00945         // the corresponding frame indices
00946         int f_idx_a = keyframe_a.index;
00947         int f_idx_b = keyframe_b.index;
00948 
00949         // the new poses of keyframes a and b (after graph solving)
00950         tf::Transform kf_pose_a = tfFromEigenAffine(keyframe_a.pose);
00951         tf::Transform kf_pose_b = tfFromEigenAffine(keyframe_b.pose);
00952 
00953         // the previous pose of keyframe a and b (before graph solving)
00954         tf::Transform kf_pose_a_prev, kf_pose_b_prev;
00955         tf::poseMsgToTF(path_msg_.poses[f_idx_a].pose, kf_pose_a_prev);
00956         tf::poseMsgToTF(path_msg_.poses[f_idx_b].pose, kf_pose_b_prev);
00957 
00958         // the motion, in the camera frame (after and before graph solving)
00959         tf::Transform kf_motion      = kf_pose_a.inverse() * kf_pose_b;
00960         tf::Transform kf_motion_prev = kf_pose_a_prev.inverse() * kf_pose_b_prev;
00961 
00962         // the correction from the graph solving
00963         tf::Transform correction = kf_motion_prev.inverse() * kf_motion;
00964 
00965         // update the poses in-between keyframes
00966         for (int f_idx = f_idx_a; f_idx < f_idx_b; ++f_idx)
00967         {
00968             // calculate interpolation scale
00969             double interp_scale = (double)(f_idx - f_idx_a) / (double)(f_idx_b - f_idx_a);
00970 
00971             // create interpolated correction translation and rotation
00972             tf::Vector3 v_interp = correction.getOrigin() * interp_scale;
00973             tf::Quaternion q_interp = tf::Quaternion::getIdentity();
00974             q_interp.slerp(correction.getRotation(), interp_scale);
00975 
00976             // create interpolated correction
00977             tf::Transform interpolated_correction;
00978             interpolated_correction.setOrigin(v_interp);
00979             interpolated_correction.setRotation(q_interp);
00980 
00981             // the previous frame pose
00982             tf::Transform frame_pose_prev;
00983             tf::poseMsgToTF(path_msg_.poses[f_idx].pose, frame_pose_prev);
00984 
00985             // the pevious frame motion
00986             tf::Transform frame_motion_prev = kf_pose_a_prev.inverse() * frame_pose_prev;
00987 
00988             // the interpolated motion
00989             tf::Transform interpolated_motion = frame_motion_prev * interpolated_correction;
00990 
00991             // calculate the interpolated pose
00992             path_new[f_idx] = keyframe_a.pose * eigenAffineFromTf(interpolated_motion);
00993         }
00994     }
00995 
00996     // update the last pose
00997     const rgbdtools::RGBDKeyframe& last_kf = keyframes_[kf_size - 1];
00998 
00999     tf::Transform last_kf_pose_prev;
01000     tf::poseMsgToTF(path_msg_.poses[last_kf.index].pose, last_kf_pose_prev);
01001 
01002     // update the poses in-between last keyframe and end of vo path
01003     for (int f_idx = last_kf.index; f_idx < f_size; ++f_idx)
01004     {
01005         // the previous frame pose
01006         tf::Transform frame_pose_prev;
01007         tf::poseMsgToTF(path_msg_.poses[f_idx].pose, frame_pose_prev);
01008 
01009         // the pevious frame motion
01010         tf::Transform frame_motion_prev = last_kf_pose_prev.inverse() * frame_pose_prev;
01011 
01012         // calculate the new pose
01013         path_new[f_idx] = last_kf.pose * eigenAffineFromTf(frame_motion_prev);
01014     }
01015 
01016     // copy over the interpolated path
01017     pathEigenAffineToROS(path_new, path_msg_);
01018 }
01019 
01020 
01021 bool RGBNavigator::savePcdMap(const std::string& path)
01022 {
01023     PointCloudT pcd_map;
01024     buildPcdMap(pcd_map);
01025 
01026     // write out
01027     pcl::PCDWriter writer;
01028     int result_pcd = writer.writeBinary<PointT>(path, pcd_map);
01029 
01030     if (result_pcd < 0) return false;
01031     else return true;
01032 }
01033 
01034 void RGBNavigator::buildPcdMap(PointCloudT& map_cloud)
01035 {
01036     PointCloudT::Ptr aggregate_cloud(new PointCloudT());
01037     aggregate_cloud->header.frame_id = fixed_frame_;
01038 
01039     // aggregate all frames into single cloud
01040     for (unsigned int kf_idx = 0; kf_idx < keyframes_.size(); ++kf_idx)
01041     {
01042         const rgbdtools::RGBDKeyframe& keyframe = keyframes_[kf_idx];
01043 
01044         PointCloudT cloud;
01045         keyframe.constructDensePointCloud(cloud, max_range_, max_stdev_);
01046 
01047         PointCloudT cloud_tf;
01048         pcl::transformPointCloud(cloud, cloud_tf, keyframe.pose);
01049         cloud_tf.header.frame_id = fixed_frame_;
01050 
01051         *aggregate_cloud += cloud_tf;
01052     }
01053 
01054     // filter cloud using voxel grid, and for max z
01055     pcl::VoxelGrid<PointT> vgf;
01056     vgf.setInputCloud(aggregate_cloud);
01057     vgf.setLeafSize(pcd_map_res_, pcd_map_res_, pcd_map_res_);
01058     vgf.setFilterFieldName("z");
01059     vgf.setFilterLimits (-std::numeric_limits<double>::infinity(), max_map_z_);
01060 
01061     vgf.filter(map_cloud);
01062 }
01063 void RGBNavigator::buildFullCloud(PointCloudT& map_cloud)
01064 {
01065     PointCloudT::Ptr aggregate_cloud(new PointCloudT());
01066     aggregate_cloud->header.frame_id = fixed_frame_;
01067 
01068     // aggregate all frames into single cloud
01069     for (unsigned int kf_idx = 0; kf_idx < keyframes_.size(); ++kf_idx)
01070     {
01071         const rgbdtools::RGBDKeyframe& keyframe = keyframes_[kf_idx];
01072 
01073         PointCloudT cloud;
01074         keyframe.constructDensePointCloud(cloud, max_range_, max_stdev_);
01075 
01076         PointCloudT cloud_tf;
01077         pcl::transformPointCloud(cloud, cloud_tf, keyframe.pose);
01078         cloud_tf.header.frame_id = fixed_frame_;
01079 
01080         *aggregate_cloud += cloud_tf;
01081     }
01082     map_cloud = *aggregate_cloud;
01083 }
01084 
01085 bool RGBNavigator::saveOctomap(const std::string& path)
01086 {
01087     bool result;
01088 
01089     if (octomap_with_color_)
01090     {
01091         octomap::ColorOcTree tree(octomap_res_);
01092         buildColorOctomap(tree);
01093         result = tree.write(path);
01094         //        std::cout << "Publishing octomap as pointcloud" << std::endl;
01095         //        octomap::point3d_list points_;
01096         //        tree.getOccupied(points_);
01097         //        PointCloudT cloud;
01098         //        for (octomap::point3d_list::iterator it=points_.begin(); it != points_.end(); ++it)
01099         //        {
01100         //            PointT point;
01101         //            point.x = it->x();
01102         //            point.y = it->y();
01103         //            point.z = it->z();
01104         //            point.rgb = 0;
01105         //            cloud.push_back(point);
01106         //        }
01107         //        cloud.header.frame_id = fixed_frame_;
01108         //        keyframes_pub_.publish(cloud);
01109     }
01110     else
01111         result = false;
01112     return result;
01113 }
01114 
01115 
01116 void RGBNavigator::buildColorOctomap(octomap::ColorOcTree& tree)
01117 {
01118     ROS_INFO("Building Octomap with color...");
01119 
01120     octomap::point3d sensor_origin(0.0, 0.0, 0.0);
01121     u_int n_original_poses = solver_.getNOriginalPoses();
01122     for (unsigned int kf_idx = 0; kf_idx < n_original_poses; ++kf_idx)
01123     {
01124         ROS_INFO("Processing keyframe %u", kf_idx);
01125         const rgbdtools::RGBDKeyframe& keyframe = keyframes_[kf_idx];
01126 
01127         // construct the cloud
01128         PointCloudT::Ptr cloud_unf(new PointCloudT());
01129         keyframe.constructDensePointCloud(*cloud_unf, max_range_, max_stdev_);
01130 
01131         // perform filtering for max z
01132         pcl::transformPointCloud(*cloud_unf, *cloud_unf, keyframe.pose);
01133         PointCloudT cloud;
01134         pcl::PassThrough<PointT> pass;
01135         pass.setInputCloud (cloud_unf);
01136         pass.setFilterFieldName ("z");
01137         pass.setFilterLimits (-std::numeric_limits<double>::infinity(), max_map_z_);
01138         pass.filter(cloud);
01139         pcl::transformPointCloud(cloud, cloud, keyframe.pose.inverse());
01140 
01141         octomap::pose6d frame_origin = poseTfToOctomap(tfFromEigenAffine(keyframe.pose));
01142 
01143         // build octomap cloud from pcl cloud
01144         octomap::Pointcloud octomap_cloud;
01145         for (unsigned int pt_idx = 0; pt_idx < cloud.points.size(); ++pt_idx)
01146         {
01147             const PointT& p = cloud.points[pt_idx];
01148             if (!std::isnan(p.z))
01149                 octomap_cloud.push_back(p.x, p.y, p.z);
01150         }
01151 
01152         // insert scan (only xyz considered, no colors)
01153         tree.insertScan(octomap_cloud, sensor_origin, frame_origin);
01154 
01155         // insert colors
01156         PointCloudT cloud_tf;
01157         pcl::transformPointCloud(cloud, cloud_tf, keyframe.pose);
01158         for (unsigned int pt_idx = 0; pt_idx < cloud_tf.points.size(); ++pt_idx)
01159         {
01160             const PointT& p = cloud_tf.points[pt_idx];
01161             if (!std::isnan(p.z))
01162             {
01163                 octomap::point3d endpoint(p.x, p.y, p.z);
01164                 octomap::ColorOcTreeNode* n = tree.search(endpoint);
01165                 if (n) n->setColor(p.r, p.g, p.b);
01166             }
01167         }
01168 
01169         tree.updateInnerOccupancy();
01170     }
01171 }
01172 
01173 void RGBNavigator::publishPath()
01174 {
01175     PathMsg kfs;
01176     kfs.header.frame_id = fixed_frame_;
01177     kfs.header.seq = 0;
01178     kfs.header.stamp = ros::Time::now();
01179     for(u_int i = solver_.n_original_poses; i < keyframes_.size(); i++)
01180     {
01181         const rgbdtools::RGBDKeyframe& keyframe=keyframes_[i];
01182 
01183         if(!keyframe.used)
01184         {
01185             continue;
01186         }
01187 
01188         geometry_msgs::PoseStamped pose;
01189         pose.header.frame_id = fixed_frame_;
01190         pose.header.seq = keyframe.header.seq;
01191         pose.header.stamp.sec = keyframe.header.stamp.sec;
01192         pose.header.stamp.nsec = keyframe.header.stamp.nsec;
01193         pose.pose.position.x = keyframe.pose(0,3);
01194         pose.pose.position.y = keyframe.pose(1,3);
01195         pose.pose.position.z = keyframe.pose(2,3);
01196         pose.pose.orientation.x = 1;
01197         pose.pose.orientation.y = 0;
01198         pose.pose.orientation.z = 0;
01199         pose.pose.orientation.w = 1;
01200         kfs.poses.push_back(pose);
01201     }
01202     if(kfs.poses.size()!=0)
01203         path_pub_.publish(kfs);
01204 }
01205 
01206 bool RGBNavigator::savePath(const std::string& filepath)
01207 {
01208     // open file
01209     std::string filename = filepath + "/path.txt";
01210     std::ofstream file(filename.c_str());
01211     if (!file.is_open()) return false;
01212 
01213     file << "# index seq stamp.sec stamp.nsec x y z qx qy qz qw" << std::endl;
01214 
01215     for (unsigned int idx = 0; idx < path_msg_.poses.size(); ++idx)
01216     {
01217         const geometry_msgs::PoseStamped& pose = path_msg_.poses[idx];
01218 
01219         file << idx << " "
01220              << pose.header.seq << " "
01221              << pose.header.stamp.sec << " "
01222              << pose.header.stamp.nsec << " "
01223              << pose.pose.position.x << " "
01224              << pose.pose.position.y << " "
01225              << pose.pose.position.z << " "
01226              << pose.pose.orientation.x << " "
01227              << pose.pose.orientation.y << " "
01228              << pose.pose.orientation.z << " "
01229              << pose.pose.orientation.w << std::endl;
01230     }
01231 
01232     file.close();
01233 
01234     return true;
01235 }
01236 
01237 bool RGBNavigator::savePathTUMFormat(const std::string& filepath)
01238 {
01239     // open file
01240     std::string filename = filepath + "/path.tum.txt";
01241     std::ofstream file(filename.c_str());
01242     if (!file.is_open()) return false;
01243 
01244     file << "# stamp x y z qx qy qz qw" << std::endl;
01245 
01246     for (unsigned int idx = 0; idx < path_msg_.poses.size(); ++idx)
01247     {
01248         const geometry_msgs::PoseStamped& pose = path_msg_.poses[idx];
01249 
01250         file << pose.header.stamp.sec << "."
01251              << pose.header.stamp.nsec << " "
01252              << pose.pose.position.x << " "
01253              << pose.pose.position.y << " "
01254              << pose.pose.position.z << " "
01255              << pose.pose.orientation.x << " "
01256              << pose.pose.orientation.y << " "
01257              << pose.pose.orientation.z << " "
01258              << pose.pose.orientation.w << std::endl;
01259     }
01260 
01261     file.close();
01262 
01263     return true;
01264 }
01265 
01266 bool RGBNavigator::loadPath(const std::string& filepath)
01267 {
01268     path_msg_.poses.clear();
01269 
01270     // open file
01271     std::string filename = filepath + "/path.txt";
01272     std::ifstream file(filename.c_str());
01273     if (!file.is_open()) return false;
01274 
01275     std::string line;
01276 
01277     // get header
01278     getline(file, line);
01279 
01280     // read each line
01281     while(std::getline(file, line))
01282     {
01283         std::istringstream is(line);
01284 
01285         // fill out pose information
01286         geometry_msgs::PoseStamped pose;
01287         pose.header.frame_id = fixed_frame_;
01288         int idx;
01289 
01290         is >> idx
01291            >> pose.header.seq
01292            >> pose.header.stamp.sec
01293            >> pose.header.stamp.nsec
01294            >> pose.pose.position.x
01295            >> pose.pose.position.y
01296            >> pose.pose.position.z
01297            >> pose.pose.orientation.x
01298            >> pose.pose.orientation.y
01299            >> pose.pose.orientation.z
01300            >> pose.pose.orientation.w;
01301 
01302         // add to poses vector
01303         path_msg_.poses.push_back(pose);
01304     }
01305 
01306     file.close();
01307     return true;
01308 }
01309 
01310 } // namespace ccny_rgbd
01311 
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends


ccny_rgbd
Author(s): Ivan Dryanovski
autogenerated on Tue Aug 27 2013 10:34:02