Enumerations | Functions
BGL Graph Properties
Pose-Graph

Boost Graph Library (BGL) properties for BGL graph PoseGraph forms the representation of of pose-graph part of our Main Data Structure (MDS). More...

Collaboration diagram for BGL Graph Properties:

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...

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)

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...

Detailed Description

Boost Graph Library (BGL) properties for BGL graph PoseGraph forms the representation of of pose-graph part of our Main Data Structure (MDS).

Vertices and edges:


Enumeration Type Documentation

matches between keypoints

Enumerator:
edge_kp_idx_map 

Definition at line 102 of file pose_graph.h.

Todo:
what is it?
Enumerator:
edge_rel_scale_error 

Definition at line 109 of file pose_graph.h.

T_c1_c2.

Todo:
consider removal, i think its redundant
Enumerator:
edge_transform 

Definition at line 106 of file pose_graph.h.

Todo:
unused, initially meant for Points class.
Enumerator:
graph_points 

Definition at line 112 of file pose_graph.h.

debugging information stored with this vertex.

Enumerator:
vertex_debug_info 

Definition at line 96 of file pose_graph.h.

stores array of vertex descriptors

Enumerator:
vertex_desc 

Definition at line 71 of file pose_graph.h.

Stores array landmark indexes.

If there is a landmark associated with a feature at an index of this array, then it stores the landmark id at the index, otherwise it stores BAD_INDEX value.

See also:
Points
Enumerator:
vertex_fix_idx 

Definition at line 81 of file pose_graph.h.

Is vertex a keyframe?

See also:
Keyframe Manager
Enumerator:
vertex_keyframe_flag 

Definition at line 93 of file pose_graph.h.

Stored array of keypoints.

Enumerator:
vertex_kp 

Definition at line 69 of file pose_graph.h.

Stores unique identifier of a vertex.

Enumerator:
vertex_seq 

Definition at line 84 of file pose_graph.h.

ROS timestamp (for the image represented by this vertex.

Enumerator:
vertex_timestamp 

Definition at line 99 of file pose_graph.h.

stores T_wc for pose corresponding to this vertex. 'c' signifies camera CF of the pose.

Enumerator:
vertex_transform 

Definition at line 87 of file pose_graph.h.


Function Documentation

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   
)
 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:14