Public Member Functions | Private Member Functions | Private Attributes
uncertain_tf::UncertainTransformListener Class Reference

#include <UncertainTransformListener.h>

Inheritance diagram for uncertain_tf::UncertainTransformListener:
Inheritance graph
[legend]

List of all members.

Public Member Functions

template<typename Derived , typename OtherDerived >
void calculateSampleCovariance (const MatrixBase< Derived > &x, const MatrixBase< Derived > &y, MatrixBase< OtherDerived > &C_)
 calculate the covariance of a given sample set in eigen type
VectorXd calculateSampleMean (const MatrixXd &x)
 calculate the covariance of a given sample set in eigen type
bool isZero (const MatrixXd mat)
 check if a covariance matrix is zero - as initialized when no cov is known
void printFrame (std::string last_frame, std::string current_frame, tf::Transform rel)
MatrixXd sampleFromMeanCov (const VectorXd &mean_, const MatrixXd &cov_, size_t n=1)
 sample n transforms given mean and cov in eigen types
void sampleFromMeanCov (const tf::Transform &mean, const MatrixXd &cov, std::vector< tf::Transform > &output, size_t n=1)
 sample n transforms given mean in tf and cov in eigen type
tf::Transform sampleFromMeanCov (const tf::Transform &mean, const MatrixXd &cov)
 sample a single transform given mean in tf and cov in eigen type
MatrixXd sampleSetTFtoMatrixXd (std::vector< tf::StampedTransform > sampleset)
 convert a vector of transforms to a eigen sampleset matrix for covariance calculation
void sampleTransform (const std::string &target_frame, const std::string &source_frame, const ros::Time &time, std::vector< StampedTransform > &output, size_t n)
 sample from frame names and time into a vector of transforms, results are push_back'ed to output
void sampleTransform (const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &time, const std::string &fixed_frame, std::vector< StampedTransform > &output, size_t n)
 sample using time travel, results are push_back'ed to output
void sampleTransformGaussianTime (const std::string &target_frame, const std::string &source_frame, const ros::Time &time_mean, const ros::Duration &time_variance, std::vector< StampedTransform > &output, size_t n)
 same as above, but now sample from a distribution for the time
void sampleTransformUniformTime (const std::string &target_frame, const std::string &source_frame, const ros::Time &time_start, const ros::Time &time_end, std::vector< StampedTransform > &output, size_t n)
 same as above, but instead of gaussian time creates samples in equal time steps
VectorXd transformTFToVectorXd (const tf::Transform &transform)
 convert from tf to eigen
tf::Transform transformVectorXdToTF (const VectorXd &vec)
 convert from eigen to tf
 UncertainTransformListener (ros::Duration max_cache_time=ros::Duration(tf::Transformer::DEFAULT_CACHE_TIME), bool spin_thread=true)

Private Member Functions

void subscription_callback (const uncertain_tf::utfMessageConstPtr &msg)

Private Attributes

EigenMultivariateNormal
< double, 6 > * 
emn_
ros::Subscriber message_subscriber_utf_
ros::NodeHandle node_
UnivariateNormal< double > * univ_

Detailed Description

Definition at line 17 of file UncertainTransformListener.h.


Constructor & Destructor Documentation

Definition at line 13 of file UncertainTransformListener.cpp.


Member Function Documentation

template<typename Derived , typename OtherDerived >
void uncertain_tf::UncertainTransformListener::calculateSampleCovariance ( const MatrixBase< Derived > &  x,
const MatrixBase< Derived > &  y,
MatrixBase< OtherDerived > &  C_ 
)

calculate the covariance of a given sample set in eigen type

Definition at line 83 of file UncertainTransformListener.h.

calculate the covariance of a given sample set in eigen type

Definition at line 24 of file UncertainTransformListener.cpp.

check if a covariance matrix is zero - as initialized when no cov is known

Definition at line 29 of file UncertainTransformListener.cpp.

void uncertain_tf::UncertainTransformListener::printFrame ( std::string  last_frame,
std::string  current_frame,
tf::Transform  rel 
)

Definition at line 120 of file UncertainTransformListener.cpp.

MatrixXd uncertain_tf::UncertainTransformListener::sampleFromMeanCov ( const VectorXd &  mean_,
const MatrixXd &  cov_,
size_t  n = 1 
)

sample n transforms given mean and cov in eigen types

Definition at line 49 of file UncertainTransformListener.cpp.

void uncertain_tf::UncertainTransformListener::sampleFromMeanCov ( const tf::Transform mean,
const MatrixXd &  cov,
std::vector< tf::Transform > &  output,
size_t  n = 1 
)

sample n transforms given mean in tf and cov in eigen type

Definition at line 69 of file UncertainTransformListener.cpp.

sample a single transform given mean in tf and cov in eigen type

Definition at line 77 of file UncertainTransformListener.cpp.

convert a vector of transforms to a eigen sampleset matrix for covariance calculation

Definition at line 38 of file UncertainTransformListener.cpp.

void uncertain_tf::UncertainTransformListener::sampleTransform ( const std::string &  target_frame,
const std::string &  source_frame,
const ros::Time time,
std::vector< StampedTransform > &  output,
size_t  n 
)

sample from frame names and time into a vector of transforms, results are push_back'ed to output

Definition at line 126 of file UncertainTransformListener.cpp.

void uncertain_tf::UncertainTransformListener::sampleTransform ( const std::string &  target_frame,
const ros::Time target_time,
const std::string &  source_frame,
const ros::Time time,
const std::string &  fixed_frame,
std::vector< StampedTransform > &  output,
size_t  n 
)

sample using time travel, results are push_back'ed to output

Definition at line 279 of file UncertainTransformListener.cpp.

void uncertain_tf::UncertainTransformListener::sampleTransformGaussianTime ( const std::string &  target_frame,
const std::string &  source_frame,
const ros::Time time_mean,
const ros::Duration time_variance,
std::vector< StampedTransform > &  output,
size_t  n 
)

same as above, but now sample from a distribution for the time

Definition at line 310 of file UncertainTransformListener.cpp.

void uncertain_tf::UncertainTransformListener::sampleTransformUniformTime ( const std::string &  target_frame,
const std::string &  source_frame,
const ros::Time time_start,
const ros::Time time_end,
std::vector< StampedTransform > &  output,
size_t  n 
)

same as above, but instead of gaussian time creates samples in equal time steps

Definition at line 333 of file UncertainTransformListener.cpp.

Definition at line 107 of file UncertainTransformListener.cpp.

convert from tf to eigen

Definition at line 87 of file UncertainTransformListener.cpp.

convert from eigen to tf

Definition at line 98 of file UncertainTransformListener.cpp.


Member Data Documentation

Definition at line 78 of file UncertainTransformListener.h.

Definition at line 77 of file UncertainTransformListener.h.

Reimplemented from tf::TransformListener.

Definition at line 76 of file UncertainTransformListener.h.

Definition at line 79 of file UncertainTransformListener.h.


The documentation for this class was generated from the following files:


uncertain_tf
Author(s): Thomas Ruehr
autogenerated on Mon Oct 6 2014 08:20:49