Classes | Public Member Functions | Protected Member Functions | Protected Attributes
PoseTracker Class Reference

#include <posetracker.h>

List of all members.

Classes

struct  MarkerEval

Public Member Functions

void init (const std::string &propFile, double scale, tf::TransformBroadcaster *bc, double _sqrErrThreshold, bool _useRansac, unsigned int _numRansacSamples)
 PoseTracker ()
void process (const visualization_msgs::MarkerArray::ConstPtr &msg)
void setDebug (bool d)

Protected Member Functions

bool calculatePose (const visualization_msgs::MarkerArray::ConstPtr &m)
double getConsensus (std::vector< MarkerEval > &points, Eigen::Affine3d &p, int &numInliers)
 returns sum of squared errors of inliers given model p
void parsePropFile (const std::string &logfile, double scale)

Protected Attributes

std::vector< std::string > bodyMarkerNames
std::vector< Eigen::Vector3d > bodyMarkerPositions
std::string bodyName
tf::TransformBroadcasterbroadcaster
bool debug
bool initialized
std::vector< MarkerEvalmarkerEval
int numRansacSamples
double sqrErrThreshold
 squared error threshold for accepting a point as inlier
bool useRansac

Detailed Description

Definition at line 25 of file posetracker.h.


Constructor & Destructor Documentation

Definition at line 18 of file posetracker.cpp.


Member Function Documentation

bool PoseTracker::calculatePose ( const visualization_msgs::MarkerArray::ConstPtr &  m) [protected]

Definition at line 60 of file posetracker.cpp.

double PoseTracker::getConsensus ( std::vector< MarkerEval > &  points,
Eigen::Affine3d &  p,
int &  numInliers 
) [protected]

returns sum of squared errors of inliers given model p

Definition at line 193 of file posetracker.cpp.

void PoseTracker::init ( const std::string &  propFile,
double  scale,
tf::TransformBroadcaster bc,
double  _sqrErrThreshold,
bool  _useRansac,
unsigned int  _numRansacSamples 
)

Definition at line 29 of file posetracker.cpp.

void PoseTracker::parsePropFile ( const std::string &  logfile,
double  scale 
) [protected]

Definition at line 255 of file posetracker.cpp.

void PoseTracker::process ( const visualization_msgs::MarkerArray::ConstPtr &  msg)

Definition at line 52 of file posetracker.cpp.

Definition at line 24 of file posetracker.cpp.


Member Data Documentation

std::vector<std::string> PoseTracker::bodyMarkerNames [protected]

Definition at line 54 of file posetracker.h.

std::vector<Eigen::Vector3d> PoseTracker::bodyMarkerPositions [protected]

Definition at line 53 of file posetracker.h.

std::string PoseTracker::bodyName [protected]

Definition at line 52 of file posetracker.h.

Definition at line 56 of file posetracker.h.

bool PoseTracker::debug [protected]

Definition at line 49 of file posetracker.h.

Definition at line 44 of file posetracker.h.

Definition at line 45 of file posetracker.h.

Definition at line 47 of file posetracker.h.

double PoseTracker::sqrErrThreshold [protected]

squared error threshold for accepting a point as inlier

Definition at line 48 of file posetracker.h.

Definition at line 46 of file posetracker.h.


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


cortex_stream
Author(s): Daniel Maier
autogenerated on Wed Oct 31 2012 08:22:56