All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines
Public Member Functions | Public Attributes
articulation_models::GenericModel Class Reference

#include <generic_model.h>

Inheritance diagram for articulation_models::GenericModel:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual double evalLatestJacobian ()
virtual bool evaluateModel ()
virtual bool fitMinMaxConfigurations ()
virtual bool fitModel ()
 GenericModel ()
virtual double getBIC ()
virtual V_Configuration getConfiguration (size_t index)
virtual size_t getDOFs ()
int getId ()
virtual double getInlierLogLikelihood (size_t index)
virtual double getLogLikelihood (bool estimate_outlier_ratio)
virtual double getLogLikelihoodForPoseIndex (size_t index)
virtual V_Configuration getMaxConfigurationObserved ()
virtual V_Configuration getMinConfigurationObserved ()
virtual articulation_msgs::ModelMsg getModel ()
virtual std::string getModelName ()
virtual double getOrientationError ()
virtual double getOutlierLogLikelihood ()
double getParam (std::string name)
void getParam (std::string name, double &data)
void getParam (std::string name, tf::Vector3 &vec)
void getParam (std::string name, tf::Quaternion &quat)
void getParam (std::string name, tf::Transform &t)
void getParam (std::string name, Eigen::VectorXd &vec)
void getParam (std::string name, Eigen::MatrixXd &mat)
virtual double getPositionError ()
virtual size_t getSamples ()
virtual articulation_msgs::TrackMsg getTrack ()
virtual bool guessParameters ()
bool hasParam (std::string name)
virtual void keepLatestPoseOnly ()
virtual bool normalizeParameters ()
virtual int openChannel (std::string name, bool autocreate=true)
virtual bool optimizeParameters ()
virtual V_Configuration predictConfiguration (geometry_msgs::Pose pose)
virtual M_CartesianJacobian predictHessian (V_Configuration q, double delta=1e-6)
virtual M_CartesianJacobian predictJacobian (V_Configuration q, double delta=1e-6)
virtual geometry_msgs::Pose predictPose (V_Configuration q)
virtual void prepareChannels ()
virtual void projectConfigurationToJacobian ()
virtual void projectConfigurationToPose ()
virtual void projectPoseToConfiguration ()
virtual void readParamsFromModel ()
virtual void sampleConfigurationSpace (double resolution)
virtual bool sampleConsensus ()
virtual void setConfiguration (size_t index, V_Configuration q)
void setId (int id)
virtual void setJacobian (size_t index, M_CartesianJacobian J)
virtual void setModel (const articulation_msgs::ModelMsg &model)
void setParam (std::string name, double value, int type)
void setParam (std::string name, const tf::Vector3 &vec, int type)
void setParam (std::string name, const tf::Quaternion &quat, int type)
void setParam (std::string name, const tf::Transform &t, int type)
void setParam (std::string name, const Eigen::VectorXd &vec, int type)
void setParam (std::string name, const Eigen::MatrixXd &mat, int type)
virtual void setTrack (const articulation_msgs::TrackMsg &track)
virtual void updateParameters (std::vector< double > delta)
virtual void writeParamsToModel ()

Public Attributes

double avg_error_orientation
double avg_error_position
double bic
std::vector< int > channelConfiguration
int channelInlierLogLikelihood
int channelLogLikelihood
int channelOutlier
double complexity
double evaluated
Eigen::MatrixXd hessian
Eigen::MatrixXd jacobian
double last_error_jacobian
double loglikelihood
articulation_msgs::ModelMsg model
double optimizer_iterations
double outlier_ratio
std::vector
< articulation_msgs::ParamMsg
params_initial
double prior_outlier_ratio
double sac_iterations
double sigma_orientation
double sigma_position
double supress_similar

Detailed Description

Definition at line 19 of file generic_model.h.


Constructor & Destructor Documentation

Definition at line 30 of file generic_model.cpp.


Member Function Documentation

Definition at line 345 of file generic_model.cpp.

Reimplemented in articulation_models::PCAGPModel.

Definition at line 277 of file generic_model.cpp.

Definition at line 269 of file generic_model.cpp.

Reimplemented in articulation_models::PCAGPModel.

Definition at line 254 of file generic_model.cpp.

Definition at line 393 of file generic_model.cpp.

Definition at line 470 of file generic_model.cpp.

Definition at line 83 of file generic_model.cpp.

Definition at line 605 of file generic_model.cpp.

double articulation_models::GenericModel::getLogLikelihood ( bool  estimate_outlier_ratio) [virtual]

Definition at line 668 of file generic_model.cpp.

Definition at line 644 of file generic_model.cpp.

Definition at line 512 of file generic_model.cpp.

Definition at line 495 of file generic_model.cpp.

Definition at line 60 of file generic_model.cpp.

Definition at line 88 of file generic_model.cpp.

Definition at line 389 of file generic_model.cpp.

Definition at line 627 of file generic_model.cpp.

double articulation_models::GenericModel::getParam ( std::string  name)

Definition at line 150 of file generic_model.cpp.

void articulation_models::GenericModel::getParam ( std::string  name,
double &  data 
)

Definition at line 160 of file generic_model.cpp.

void articulation_models::GenericModel::getParam ( std::string  name,
tf::Vector3 &  vec 
)

Definition at line 170 of file generic_model.cpp.

void articulation_models::GenericModel::getParam ( std::string  name,
tf::Quaternion quat 
)

Definition at line 176 of file generic_model.cpp.

void articulation_models::GenericModel::getParam ( std::string  name,
tf::Transform t 
)

Definition at line 183 of file generic_model.cpp.

void articulation_models::GenericModel::getParam ( std::string  name,
Eigen::VectorXd &  vec 
)

Definition at line 165 of file generic_model.cpp.

void articulation_models::GenericModel::getParam ( std::string  name,
Eigen::MatrixXd &  mat 
)

Definition at line 191 of file generic_model.cpp.

Definition at line 385 of file generic_model.cpp.

Definition at line 96 of file generic_model.cpp.

Definition at line 75 of file generic_model.cpp.

Definition at line 240 of file generic_model.cpp.

Definition at line 594 of file generic_model.cpp.

int articulation_models::GenericModel::openChannel ( std::string  name,
bool  autocreate = true 
) [virtual]

Definition at line 249 of file generic_model.cpp.

Definition at line 791 of file generic_model.cpp.

Reimplemented in articulation_models::PrismaticModel.

Definition at line 416 of file generic_model.cpp.

Definition at line 404 of file generic_model.cpp.

Definition at line 139 of file generic_model.cpp.

Reimplemented in articulation_models::PCAGPModel.

Definition at line 548 of file generic_model.cpp.

Reimplemented in articulation_models::PCAGPModel.

Definition at line 539 of file generic_model.cpp.

Reimplemented in articulation_models::PCAGPModel.

Definition at line 530 of file generic_model.cpp.

void articulation_models::GenericModel::sampleConfigurationSpace ( double  resolution) [virtual]

Definition at line 557 of file generic_model.cpp.

Definition at line 717 of file generic_model.cpp.

void articulation_models::GenericModel::setConfiguration ( size_t  index,
V_Configuration  q 
) [virtual]

Definition at line 443 of file generic_model.cpp.

Definition at line 79 of file generic_model.cpp.

void articulation_models::GenericModel::setJacobian ( size_t  index,
M_CartesianJacobian  J 
) [virtual]

Definition at line 458 of file generic_model.cpp.

Definition at line 54 of file generic_model.cpp.

void articulation_models::GenericModel::setParam ( std::string  name,
double  value,
int  type 
)

Definition at line 197 of file generic_model.cpp.

void articulation_models::GenericModel::setParam ( std::string  name,
const tf::Vector3 &  vec,
int  type 
)

Definition at line 216 of file generic_model.cpp.

void articulation_models::GenericModel::setParam ( std::string  name,
const tf::Quaternion quat,
int  type 
)

Definition at line 222 of file generic_model.cpp.

void articulation_models::GenericModel::setParam ( std::string  name,
const tf::Transform t,
int  type 
)

Definition at line 229 of file generic_model.cpp.

void articulation_models::GenericModel::setParam ( std::string  name,
const Eigen::VectorXd &  vec,
int  type 
)

Definition at line 211 of file generic_model.cpp.

void articulation_models::GenericModel::setParam ( std::string  name,
const Eigen::MatrixXd &  mat,
int  type 
)

Definition at line 234 of file generic_model.cpp.

Definition at line 70 of file generic_model.cpp.


Member Data Documentation

Definition at line 32 of file generic_model.h.

Definition at line 31 of file generic_model.h.

Definition at line 34 of file generic_model.h.

Definition at line 46 of file generic_model.h.

Definition at line 45 of file generic_model.h.

Definition at line 44 of file generic_model.h.

Definition at line 43 of file generic_model.h.

Definition at line 30 of file generic_model.h.

Definition at line 41 of file generic_model.h.

Definition at line 37 of file generic_model.h.

Definition at line 36 of file generic_model.h.

Definition at line 39 of file generic_model.h.

Definition at line 33 of file generic_model.h.

Definition at line 48 of file generic_model.h.

Definition at line 27 of file generic_model.h.

Definition at line 25 of file generic_model.h.

Definition at line 118 of file generic_model.h.

Definition at line 35 of file generic_model.h.

Definition at line 26 of file generic_model.h.

Definition at line 23 of file generic_model.h.

Definition at line 22 of file generic_model.h.

Definition at line 24 of file generic_model.h.


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


articulation_models
Author(s): Juergen Sturm
autogenerated on Wed Dec 26 2012 15:35:18