Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes | Static Protected Attributes
Node Class Reference

Holds the data for one graph node and provides functionality to compute relative transformations to other Nodes. More...

#include <node.h>

List of all members.

Public Member Functions

void addPointCloud (pointcloud_type::Ptr pc_col)
void buildFlannIndex ()
void clearFeatureInformation ()
void clearPointCloud ()
 erase the points from the cloud to save memory
unsigned int featureMatching (const Node *other, std::vector< cv::DMatch > *matches) const
tf::StampedTransform getBase2PointsTransform ()
 Transform, e.g., from kinematics.
tf::StampedTransform getGroundTruthTransform ()
 Transform, e.g., from MoCap.
tf::StampedTransform getOdomTransform ()
 Transform, e.g., from Joint/Wheel odometry.
bool getRelativeTransformationTo (const Node *target_node, std::vector< cv::DMatch > *initial_matches, Eigen::Matrix4f &resulting_transformation, float &rmse, std::vector< cv::DMatch > &matches) const
 Compute the relative transformation between the nodes.
MatchingResult matchNodePair (const Node *older_node)
 Compare the features of two nodes and compute the transformation.
 Node (const cv::Mat &visual, const cv::Mat &depth, const cv::Mat &detection_mask, const sensor_msgs::CameraInfoConstPtr &cam_info, std_msgs::Header depth_header, cv::Ptr< cv::FeatureDetector > detector, cv::Ptr< cv::DescriptorExtractor > extractor)
 Node (const cv::Mat visual, cv::Ptr< cv::FeatureDetector > detector, cv::Ptr< cv::DescriptorExtractor > extractor, pointcloud_type::Ptr point_cloud, const cv::Mat detection_mask=cv::Mat())
 Node ()
void publish (ros::Time timestamp, ros::Publisher pub)
 Send own pointcloud with given frame, publisher and timestamp.
void setBase2PointsTransform (tf::StampedTransform &b2p)
 Transform, e.g., from kinematics.
void setGroundTruthTransform (tf::StampedTransform gt)
 Transform, e.g., from MoCap.
void setOdomTransform (tf::StampedTransform odom)
 Transform, e.g., from Joint/Wheel odometry.
 ~Node ()
 Delete the flannIndex if built.

Public Attributes

std::vector< std::pair< float,
float > > 
feature_depth_stats_
 Contains the minimum and maximum depth in the feature's range (not used yet)
cv::Mat feature_descriptors_
 descriptor definitions
std::vector< cv::KeyPoint > feature_locations_2d_
 Where in the image are the descriptors.
std::vector< Eigen::Vector4f,
Eigen::aligned_allocator
< Eigen::Vector4f > > 
feature_locations_3d_
 backprojected 3d descriptor locations relative to cam position in homogeneous coordinates (last dimension is 1.0)
unsigned int id_
 pointcloud_type centrally defines what the pc is templated on
pointcloud_type::Ptr pc_col
 must correspond to the g2o vertex id
std::vector< floatsiftgpu_descriptors

Protected Member Functions

template<class CONTAINER >
void computeInliersAndError (const CONTAINER &initial_matches, const Eigen::Matrix4f &transformation, const std::vector< Eigen::Vector4f, Eigen::aligned_allocator< Eigen::Vector4f > > &origins, const std::vector< std::pair< float, float > > origins_depth_stats, const std::vector< Eigen::Vector4f, Eigen::aligned_allocator< Eigen::Vector4f > > &targets, const std::vector< std::pair< float, float > > targets_depth_stats, std::vector< cv::DMatch > &new_inliers, double &mean_error, std::vector< double > &errors, double squaredMaxInlierDistInM=0.0009) const
template<class CONTAINER >
Eigen::Matrix4f getTransformFromMatches (const Node *other_node, const CONTAINER &matches, bool &valid, float max_dist_m=-1) const
template<class CONTAINER >
Eigen::Matrix4f getTransformFromMatchesUmeyama (const Node *other_node, CONTAINER matches) const
void mat2dist (const Eigen::Matrix4f &t, double &dist)
 Get the norm of the translational part of an affine matrix (Helper for isBigTrafo)
void projectTo3D (std::vector< cv::KeyPoint > &feature_locations_2d, std::vector< Eigen::Vector4f, Eigen::aligned_allocator< Eigen::Vector4f > > &feature_locations_3d, const pointcloud_type::ConstPtr point_cloud)
 return the 3D projection of valid keypoints using information from the point cloud and remove invalid keypoints (NaN depth)
void projectTo3D (std::vector< cv::KeyPoint > &feature_locations_2d, std::vector< Eigen::Vector4f, Eigen::aligned_allocator< Eigen::Vector4f > > &feature_locations_3d, const cv::Mat &depth, const sensor_msgs::CameraInfoConstPtr &cam_info)
 return the 3D projection of valid keypoints using information from the depth image and remove invalid keypoints (NaN depth)
void retrieveBase2CamTransformation ()
 Retrieves and stores the transformation from base to point cloud at capturing time.

Protected Attributes

tf::StampedTransform base2points_
 contains the transformation from the base (defined on param server) to the point_cloud
cv::flann::IndexflannIndex
tf::StampedTransform ground_truth_transform_
 contains the transformation from the mocap system
int initial_node_matches_
tf::StampedTransform odom_transform_
 contains the transformation from the wheel encoders/joint states

Static Protected Attributes

static QMutex gicp_mutex
static QMutex siftgpu_mutex

Detailed Description

Holds the data for one graph node and provides functionality to compute relative transformations to other Nodes.

Definition at line 58 of file node.h.


Constructor & Destructor Documentation

Node::Node ( const cv::Mat &  visual,
const cv::Mat &  depth,
const cv::Mat &  detection_mask,
const sensor_msgs::CameraInfoConstPtr &  cam_info,
std_msgs::Header  depth_header,
cv::Ptr< cv::FeatureDetector >  detector,
cv::Ptr< cv::DescriptorExtractor >  extractor 
)

Visual must be CV_8UC1, depth CV_32FC1, detection_mask must be CV_8UC1 with non-zero at potential keypoint locations

Definition at line 51 of file node.cpp.

Node::Node ( const cv::Mat  visual,
cv::Ptr< cv::FeatureDetector >  detector,
cv::Ptr< cv::DescriptorExtractor >  extractor,
pointcloud_type::Ptr  point_cloud,
const cv::Mat  detection_mask = cv::Mat() 
)

Visual must be CV_8UC1 detection_mask must be CV_8UC1 with non-zero at potential keypoint locations

Definition at line 130 of file node.cpp.

Node::Node ( ) [inline]

Definition at line 79 of file node.h.

Delete the flannIndex if built.

Definition at line 228 of file node.cpp.


Member Function Documentation

void Node::addPointCloud ( pointcloud_type::Ptr  pc_col)

Definition at line 1230 of file node.cpp.

Definition at line 389 of file node.cpp.

Definition at line 1222 of file node.cpp.

erase the points from the cloud to save memory

Definition at line 1233 of file node.cpp.

template<class CONTAINER >
void Node::computeInliersAndError ( const CONTAINER &  initial_matches,
const Eigen::Matrix4f &  transformation,
const std::vector< Eigen::Vector4f, Eigen::aligned_allocator< Eigen::Vector4f > > &  origins,
const std::vector< std::pair< float, float > >  origins_depth_stats,
const std::vector< Eigen::Vector4f, Eigen::aligned_allocator< Eigen::Vector4f > > &  targets,
const std::vector< std::pair< float, float > >  targets_depth_stats,
std::vector< cv::DMatch > &  new_inliers,
double &  mean_error,
std::vector< double > &  errors,
double  squaredMaxInlierDistInM = 0.0009 
) const [protected]

Definition at line 792 of file node.cpp.

unsigned int Node::featureMatching ( const Node other,
std::vector< cv::DMatch > *  matches 
) const

Fills "matches" and returns ratio of "good" features in the sense of distinction via the "nn_distance_ratio" setting (see parameter server)

Definition at line 407 of file node.cpp.

Transform, e.g., from kinematics.

Definition at line 247 of file node.cpp.

Transform, e.g., from MoCap.

Definition at line 244 of file node.cpp.

Transform, e.g., from Joint/Wheel odometry.

Definition at line 241 of file node.cpp.

bool Node::getRelativeTransformationTo ( const Node earlier_node,
std::vector< cv::DMatch > *  initial_matches,
Eigen::Matrix4f &  resulting_transformation,
float rmse,
std::vector< cv::DMatch > &  matches 
) const

Compute the relative transformation between the nodes.

Find transformation with largest support, RANSAC style. Return false if no transformation can be found

Iterations with more than half of the initial_matches inlying, count twice

Iterations with more than 80% of the initial_matches inlying, count threefold

Definition at line 904 of file node.cpp.

template<class CONTAINER >
Eigen::Matrix4f Node::getTransformFromMatches ( const Node other_node,
const CONTAINER &  matches,
bool valid,
float  max_dist_m = -1 
) const [protected]

Definition at line 864 of file node.cpp.

template<class CONTAINER >
Eigen::Matrix4f Node::getTransformFromMatchesUmeyama ( const Node other_node,
CONTAINER  matches 
) const [protected]

Definition at line 848 of file node.cpp.

void Node::mat2dist ( const Eigen::Matrix4f &  t,
double &  dist 
) [inline, protected]

Get the norm of the translational part of an affine matrix (Helper for isBigTrafo)

Definition at line 217 of file node.h.

MatchingResult Node::matchNodePair ( const Node older_node)

Compare the features of two nodes and compute the transformation.

(double)mr.all_matches.size();

Definition at line 1090 of file node.cpp.

void Node::projectTo3D ( std::vector< cv::KeyPoint > &  feature_locations_2d,
std::vector< Eigen::Vector4f, Eigen::aligned_allocator< Eigen::Vector4f > > &  feature_locations_3d,
const pointcloud_type::ConstPtr  point_cloud 
) [protected]

return the 3D projection of valid keypoints using information from the point cloud and remove invalid keypoints (NaN depth)

Definition at line 698 of file node.cpp.

void Node::projectTo3D ( std::vector< cv::KeyPoint > &  feature_locations_2d,
std::vector< Eigen::Vector4f, Eigen::aligned_allocator< Eigen::Vector4f > > &  feature_locations_3d,
const cv::Mat &  depth,
const sensor_msgs::CameraInfoConstPtr &  cam_info 
) [protected]

return the 3D projection of valid keypoints using information from the depth image and remove invalid keypoints (NaN depth)

Definition at line 738 of file node.cpp.

void Node::publish ( ros::Time  timestamp,
ros::Publisher  pub 
)

Send own pointcloud with given frame, publisher and timestamp.

Definition at line 251 of file node.cpp.

Retrieves and stores the transformation from base to point cloud at capturing time.

Transform, e.g., from kinematics.

Definition at line 238 of file node.cpp.

Transform, e.g., from MoCap.

Definition at line 235 of file node.cpp.

Transform, e.g., from Joint/Wheel odometry.

Definition at line 232 of file node.cpp.


Member Data Documentation

contains the transformation from the base (defined on param server) to the point_cloud

Definition at line 174 of file node.h.

Contains the minimum and maximum depth in the feature's range (not used yet)

Definition at line 165 of file node.h.

descriptor definitions

Definition at line 156 of file node.h.

Where in the image are the descriptors.

Definition at line 163 of file node.h.

std::vector<Eigen::Vector4f, Eigen::aligned_allocator<Eigen::Vector4f> > Node::feature_locations_3d_

backprojected 3d descriptor locations relative to cam position in homogeneous coordinates (last dimension is 1.0)

Definition at line 159 of file node.h.

Definition at line 173 of file node.h.

QMutex Node::gicp_mutex [static, protected]

Definition at line 171 of file node.h.

contains the transformation from the mocap system

Definition at line 175 of file node.h.

unsigned int Node::id_

pointcloud_type centrally defines what the pc is templated on

Definition at line 153 of file node.h.

int Node::initial_node_matches_ [protected]

Definition at line 177 of file node.h.

contains the transformation from the wheel encoders/joint states

Definition at line 176 of file node.h.

pointcloud_type::Ptr Node::pc_col

must correspond to the g2o vertex id

Definition at line 154 of file node.h.

Definition at line 160 of file node.h.

QMutex Node::siftgpu_mutex [static, protected]

Definition at line 172 of file node.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


rgbdslam
Author(s): Felix Endres, Juergen Hess, Nikolas Engelhard
autogenerated on Wed Dec 26 2012 15:53:09