Classes | Namespaces | Typedefs | Enumerations | Functions | Variables
pose_graph.h File Reference

Interface for Main Data Structure. More...

#include "utils.h"
#include "tf/transform_listener.h"
#include "sensor_msgs/CameraInfo.h"
#include "sensor_msgs/CompressedImage.h"
#include "cv_bridge/cv_bridge.h"
#include "image_transport/image_transport.h"
#include "Sophus/se3.h"
#include "feature_matching.h"
#include <vector>
#include <string>
#include <iostream>
#include <fstream>
#include <opencv2/core/core.hpp>
#include <opencv2/imgproc/imgproc.hpp>
#include <opencv2/highgui/highgui.hpp>
#include <opencv2/features2d/features2d.hpp>
#include <opencv2/calib3d/calib3d.hpp>
#include <assert.h>
#include <algorithm>
#include <boost/graph/adjacency_list.hpp>
#include <boost/graph/depth_first_search.hpp>
#include <map>
#include <boost/graph/dijkstra_shortest_paths.hpp>
#include <cmath>
#include <tr1/functional>
#include "graph_builder.h"
Include dependency graph for pose_graph.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

class  vslam::AllWeightsOneWeightMap< PoseGraphT >
 property map that represents edge weights in the graph, where all edges have weight 1. More...
class  vslam::CustomOneDetectorNodeBuilder< PoseGraphT >
class  vslam::CustomOneDetectorNodeBuilderFeature2D< PoseGraphT >
class  vslam::EdgeBuilder< G >
 Interface for adding edges to the pose-graph. More...
class  vslam::FeatureID< G >
 unique identification af landmark observation (feature) in the pose-graph. More...
class  vslam::MonoFtrClassEdgeBuilder< G >
 Implementation of EdgeBuilder, where there is only one kind of feature detector-descriptor pair. More...
class  vslam::NMSOptions
 Set up non-maxima supression (NMS) functionality of OneDetectorNodeBuilder. More...
class  vslam::OneDetectorNodeBuilder< PoseGraphT >
 Interface for adding and removing nodes in the pose-graph. More...
class  vslam::PerformanceLogger< G >
 Records time elapsed between construction and destruction of this object. More...
class  vslam::Points< G >
struct  boost::property_traits< vslam::AllWeightsOneWeightMap< PoseGraphT > >
 property map that represents edge weights in the graph, where all edges have weight 1. More...
class  vslam::VertexDebugInfo
 Debugging info for a vertex. More...

Namespaces

namespace  boost
 

??


namespace  vslam
 

Namespace containing implementation of visual odometry.


namespace  vslam::lmdetails
 

Implementation details of Landmark Manager module.


Typedefs

typedef ALIGNED< pair< int,
Vector3d > >::vector 
vslam::IdxPoint3dVec
typedef graph_traits
< PoseGraph >::edge_descriptor 
vslam::PGEdgeD
typedef graph_traits
< PoseGraph >
::vertex_descriptor 
vslam::PGVertexD
typedef boost::adjacency_list
< boost::vecS, boost::vecS,
boost::directedS,
boost::property< vertex_kp_t,
std::vector< cv::KeyPoint >
, boost::property
< vertex_desc_t, cv::Mat,
boost::property
< vertex_fix_idx_t, vector
< int >, boost::property
< vertex_seq_t, int,
boost::property
< boost::vertex_keyframe_flag_t,
int, boost::property
< boost::vertex_debug_info_t,
VertexDebugInfo,
boost::property
< boost::vertex_timestamp_t,
uint64_t, boost::property
< vertex_transform_t, SE3 >
> > > > > > >, boost::property
< edge_kp_idx_map_t, map< int,
int >, boost::property
< edge_transform_t, SE3,
boost::property
< edge_rel_scale_error_t,
double > > > > 
vslam::PoseGraph
 representation of a pose-graph.

Enumerations

enum  boost::edge_kp_idx_map_t { boost::edge_kp_idx_map = 201 }
 matches between keypoints More...
enum  boost::edge_rel_scale_error_t { boost::edge_rel_scale_error = 203 }
enum  boost::edge_transform_t { boost::edge_transform = 202 }
 T_c1_c2. More...
enum  boost::graph_points_t { boost::graph_points = 301 }
enum  boost::vertex_debug_info_t { boost::vertex_debug_info = 107 }
 debugging information stored with this vertex. More...
enum  boost::vertex_fix_idx_t { boost::vertex_fix_idx = 103 }
 Stores array landmark indexes. More...
enum  boost::vertex_keyframe_flag_t { boost::vertex_keyframe_flag = 106 }
 Is vertex a keyframe? More...
enum  boost::vertex_seq_t { boost::vertex_seq = 104 }
 Stores unique identifier of a vertex. More...
enum  boost::vertex_timestamp_t { boost::vertex_timestamp = 108 }
 ROS timestamp (for the image represented by this vertex. More...
enum  boost::vertex_transform_t { boost::vertex_transform = 105 }
 stores T_wc for pose corresponding to this vertex. 'c' signifies camera CF of the pose. More...
Image representation

Each image is reduced into an array of keypoints and array of descriptors. The indices in the arrays correspond to feature id in a given vertex and pose-graph uniquie feature id if given by FeatureID.

enum  boost::vertex_kp_t { boost::vertex_kp = 101 }
 Stored array of keypoints. More...
enum  boost::vertex_desc_t { boost::vertex_desc = 102 }
 stores array of vertex descriptors More...

Functions

 boost::BOOST_INSTALL_PROPERTY (vertex, kp)
 boost::BOOST_INSTALL_PROPERTY (vertex, desc)
 boost::BOOST_INSTALL_PROPERTY (vertex, fix_idx)
 boost::BOOST_INSTALL_PROPERTY (vertex, seq)
 boost::BOOST_INSTALL_PROPERTY (vertex, transform)
 boost::BOOST_INSTALL_PROPERTY (vertex, keyframe_flag)
 boost::BOOST_INSTALL_PROPERTY (vertex, debug_info)
 boost::BOOST_INSTALL_PROPERTY (vertex, timestamp)
 boost::BOOST_INSTALL_PROPERTY (edge, kp_idx_map)
 boost::BOOST_INSTALL_PROPERTY (edge, transform)
 boost::BOOST_INSTALL_PROPERTY (edge, rel_scale_error)
 boost::BOOST_INSTALL_PROPERTY (graph, points)
std::tr1::shared_ptr
< RobustFeatureMatcher
vslam::constructRMatcher (std::tr1::shared_ptr< cv::DescriptorMatcher > _dmatcher, std::tr1::shared_ptr< EMatrixModelBuilder > _minbuilder, std::tr1::shared_ptr< EMatrixModelBuilder > _builder)
template<class PoseGraphT >
int vslam::get (AllWeightsOneWeightMap< PoseGraphT > pmap, typename boost::property_traits< AllWeightsOneWeightMap< PoseGraphT > >::key_type vd)
 interface for property map that represents edge weights in the graph, where all edges have weight 1.
template<class G >
bool vslam::isLandmakFeature (const G &g, const FeatureID< G > &fid)
 Test if given feature has landmark associated with it.

Variables

const int vslam::BAD_INDEX = -1
 value for undefined array index.

Detailed Description

Interface for Main Data Structure.

Contains necessary forward declarations for graph_builder.h, which should be included in code that wants to use Main Data Structure.

Definition in file pose_graph.h.

 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Defines


pose_estimation
Author(s): Jiri Divis/jiridivis@gmail.com
autogenerated on Wed Mar 27 2013 21:00:13