keyframe_mapper.h
Go to the documentation of this file.
00001 
00024 #ifndef CCNY_RGBD_KEYFRAME_MAPPER_H
00025 #define CCNY_RGBD_KEYFRAME_MAPPER_H
00026 
00027 #include <ros/ros.h>
00028 #include <ros/publisher.h>
00029 #include <pcl/point_cloud.h>
00030 #include <pcl_ros/point_cloud.h>
00031 #include <pcl_ros/transforms.h>
00032 #include <tf/transform_listener.h>
00033 #include <visualization_msgs/Marker.h>
00034 #include <boost/regex.hpp>
00035 #include <octomap/octomap.h>
00036 #include <octomap/OcTree.h>
00037 #include <octomap/ColorOcTree.h>
00038 
00039 #include "ccny_rgbd/types.h"
00040 #include "ccny_rgbd/structures/rgbd_frame.h"
00041 #include "ccny_rgbd/structures/rgbd_keyframe.h"
00042 #include "ccny_rgbd/mapping/keyframe_graph_detector.h"
00043 #include "ccny_rgbd/mapping/keyframe_graph_solver_g2o.h"
00044 
00045 #include "ccny_rgbd/GenerateGraph.h"
00046 #include "ccny_rgbd/SolveGraph.h"
00047 #include "ccny_rgbd/AddManualKeyframe.h"
00048 #include "ccny_rgbd/PublishKeyframe.h"
00049 #include "ccny_rgbd/PublishKeyframes.h"
00050 #include "ccny_rgbd/Save.h"
00051 #include "ccny_rgbd/Load.h"
00052 
00053 namespace ccny_rgbd {
00054 
00068 class KeyframeMapper
00069 {
00070   public:
00071 
00076     KeyframeMapper(const ros::NodeHandle& nh, 
00077                    const ros::NodeHandle& nh_private);
00078     
00081     virtual ~KeyframeMapper();
00082 
00097     bool publishKeyframesSrvCallback(
00098       PublishKeyframes::Request& request,
00099       PublishKeyframes::Response& response);
00100 
00105     bool publishKeyframeSrvCallback(
00106       PublishKeyframe::Request& request,
00107       PublishKeyframe::Response& response);
00108 
00114     bool saveKeyframesSrvCallback(
00115       Save::Request& request,
00116       Save::Response& response);
00117 
00126     bool savePcdMapSrvCallback(
00127       Save::Request& request,
00128       Save::Response& response);
00129     
00138     bool saveOctomapSrvCallback(
00139       Save::Request& request,
00140       Save::Response& response);
00141     
00147     bool loadKeyframesSrvCallback(
00148       Load::Request& request,
00149       Load::Response& response);
00150 
00153     bool addManualKeyframeSrvCallback(
00154       AddManualKeyframe::Request& request,
00155       AddManualKeyframe::Response& response);
00156     
00160      bool generateGraphSrvCallback(
00161       GenerateGraph::Request& request,
00162       GenerateGraph::Response& response);
00163 
00169     bool solveGraphSrvCallback(
00170       SolveGraph::Request& request,
00171       SolveGraph::Response& response);
00172     
00173   protected:
00174 
00175     ros::NodeHandle nh_;          
00176     ros::NodeHandle nh_private_;  
00177     
00178     std::string fixed_frame_;     
00179     
00180     int queue_size_;  
00181     
00182     KeyframeVector keyframes_;    
00183     
00190     virtual void RGBDCallback(const ImageMsg::ConstPtr& rgb_msg,
00191                               const ImageMsg::ConstPtr& depth_msg,
00192                               const CameraInfoMsg::ConstPtr& info_msg);
00193 
00194   private:
00195 
00196     ros::Publisher keyframes_pub_;    
00197     ros::Publisher poses_pub_;        
00198     ros::Publisher kf_assoc_pub_;     
00199     ros::Publisher path_pub_;         
00200     
00202     ros::ServiceServer generate_graph_service_;
00203     
00205     ros::ServiceServer solve_graph_service_;   
00206     
00208     ros::ServiceServer pub_keyframe_service_;
00209     
00211     ros::ServiceServer pub_keyframes_service_;
00212     
00214     ros::ServiceServer save_kf_service_;
00215     
00217     ros::ServiceServer save_pcd_map_service_;
00218     
00220     ros::ServiceServer save_octomap_service_;
00221     
00223     ros::ServiceServer load_kf_service_;
00224     
00226     ros::ServiceServer add_manual_keyframe_service_;
00227 
00228     tf::TransformListener tf_listener_; 
00229 
00231     boost::shared_ptr<ImageTransport> rgb_it_;
00232     
00234     boost::shared_ptr<ImageTransport> depth_it_;
00235     
00237     boost::shared_ptr<RGBDSynchronizer3> sync_;
00238           
00240     ImageSubFilter      sub_rgb_;
00241     
00243     ImageSubFilter      sub_depth_;  
00244    
00246     CameraInfoSubFilter sub_info_;
00247     
00248     // params
00249     double pcd_map_res_; 
00250     double octomap_res_;  
00251     double kf_dist_eps_;  
00252     double kf_angle_eps_; 
00253     bool octomap_with_color_; 
00254           
00255     // state vars
00256     bool manual_add_;   
00257 
00258     KeyframeGraphDetector graph_detector_;  
00259     KeyframeGraphSolver * graph_solver_;    
00260 
00261     KeyframeAssociationVector associations_; 
00262     
00263     PathMsg path_msg_;    
00264     
00272     bool processFrame(const RGBDFrame& frame, const tf::Transform& pose);
00273     
00279     void addKeyframe(const RGBDFrame& frame, const tf::Transform& pose);
00280 
00284     void publishKeyframeData(int i);
00285     
00289     void publishKeyframePose(int i);
00290         
00293     void publishKeyframeAssociations();
00294     
00297     void publishKeyframePoses();
00298     
00301     void publishPath();
00302     
00308     bool savePcdMap(const std::string& path);
00309            
00313     void buildPcdMap(PointCloudT& map_cloud);
00314                    
00320     bool saveOctomap(const std::string& path);
00321     
00325     void buildOctomap(octomap::OcTree& tree);
00326     
00330     void buildColorOctomap(octomap::ColorOcTree& tree);
00331         
00336     static inline octomap::pose6d poseTfToOctomap(
00337       const tf::Pose& poseTf)
00338     {
00339       return octomap::pose6d(
00340               pointTfToOctomap(poseTf.getOrigin()),
00341               quaternionTfToOctomap(poseTf.getRotation()));
00342     }
00343    
00348     static inline octomap::point3d pointTfToOctomap(
00349       const tf::Point& ptTf)
00350     {
00351       return octomap::point3d(ptTf.x(), ptTf.y(), ptTf.z());
00352     }
00353    
00358     static inline octomath::Quaternion quaternionTfToOctomap(
00359       const tf::Quaternion& qTf)
00360     {
00361       return octomath::Quaternion(qTf.w(), qTf.x(), qTf.y(), qTf.z());
00362     }
00363 };
00364 
00365 } // namespace ccny_rgbd
00366 
00367 #endif // CCNY_RGBD_KEYFRAME_MAPPER_H
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends


ccny_rgbd
Author(s): Ivan Dryanovski
autogenerated on Fri Apr 12 2013 20:38:48