#include <pca_gp_model.h>
Public Member Functions | |
void | buildGPs () |
void | checkInitialized () |
bool | evaluateModel () |
bool | fitModel () |
size_t | getDOFs () |
bool | normalizeParameters () |
PCAGPModel () | |
btTransform | pose (size_t index) |
V_Configuration | predictConfiguration (geometry_msgs::Pose pose) |
geometry_msgs::Pose | predictPose (V_Configuration q) |
void | projectConfigurationToJacobian () |
void | projectConfigurationToPose () |
void | projectPoseToConfiguration () |
void | readParamsFromModel () |
void | storeData (bool inliersOnly) |
void | writeParamsToModel () |
virtual | ~PCAGPModel () |
Public Attributes | |
double | downsample |
std::vector < gaussian_process::SingleGP * > | gp |
bool | initialized |
btVector3 | prismatic_dir |
btVector3 | rigid_position |
size_t | training_samples |
Definition at line 15 of file pca_gp_model.h.
articulation_models::PCAGPModel::PCAGPModel | ( | ) |
Definition at line 32 of file pca_gp_model.cpp.
articulation_models::PCAGPModel::~PCAGPModel | ( | ) | [virtual] |
Definition at line 55 of file pca_gp_model.cpp.
void articulation_models::PCAGPModel::buildGPs | ( | ) |
Definition at line 152 of file pca_gp_model.cpp.
void articulation_models::PCAGPModel::checkInitialized | ( | ) |
Definition at line 295 of file pca_gp_model.cpp.
bool articulation_models::PCAGPModel::evaluateModel | ( | ) | [virtual] |
Reimplemented from articulation_models::GenericModel.
Definition at line 317 of file pca_gp_model.cpp.
bool articulation_models::PCAGPModel::fitModel | ( | ) | [virtual] |
Reimplemented from articulation_models::GenericModel.
Definition at line 125 of file pca_gp_model.cpp.
size_t articulation_models::PCAGPModel::getDOFs | ( | ) | [inline, virtual] |
Reimplemented from articulation_models::GenericModel.
Definition at line 33 of file pca_gp_model.h.
bool articulation_models::PCAGPModel::normalizeParameters | ( | ) | [virtual] |
Reimplemented from articulation_models::GenericModel.
Definition at line 322 of file pca_gp_model.cpp.
btTransform articulation_models::PCAGPModel::pose | ( | size_t | index | ) |
Definition at line 84 of file pca_gp_model.cpp.
V_Configuration articulation_models::PCAGPModel::predictConfiguration | ( | geometry_msgs::Pose | pose | ) | [virtual] |
Reimplemented from articulation_models::GenericModel.
Definition at line 253 of file pca_gp_model.cpp.
geometry_msgs::Pose articulation_models::PCAGPModel::predictPose | ( | V_Configuration | q | ) | [virtual] |
Reimplemented from articulation_models::GenericModel.
Definition at line 264 of file pca_gp_model.cpp.
void articulation_models::PCAGPModel::projectConfigurationToJacobian | ( | ) | [virtual] |
Reimplemented from articulation_models::GenericModel.
Definition at line 312 of file pca_gp_model.cpp.
void articulation_models::PCAGPModel::projectConfigurationToPose | ( | ) | [virtual] |
Reimplemented from articulation_models::GenericModel.
Definition at line 307 of file pca_gp_model.cpp.
void articulation_models::PCAGPModel::projectPoseToConfiguration | ( | ) | [virtual] |
Reimplemented from articulation_models::GenericModel.
Definition at line 302 of file pca_gp_model.cpp.
void articulation_models::PCAGPModel::readParamsFromModel | ( | ) | [virtual] |
Reimplemented from articulation_models::GenericModel.
Definition at line 63 of file pca_gp_model.cpp.
void articulation_models::PCAGPModel::storeData | ( | bool | inliersOnly | ) |
Definition at line 90 of file pca_gp_model.cpp.
void articulation_models::PCAGPModel::writeParamsToModel | ( | ) | [virtual] |
Reimplemented from articulation_models::GenericModel.
Definition at line 76 of file pca_gp_model.cpp.
Definition at line 23 of file pca_gp_model.h.
std::vector<gaussian_process::SingleGP*> articulation_models::PCAGPModel::gp |
Definition at line 22 of file pca_gp_model.h.
Definition at line 24 of file pca_gp_model.h.
Definition at line 16 of file pca_gp_model.h.
Definition at line 15 of file pca_gp_model.h.
Definition at line 17 of file pca_gp_model.h.