#include <generic_model.h>

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 () |
| void | getParam (std::string name, Eigen::MatrixXd &mat) |
| void | getParam (std::string name, Eigen::VectorXd &vec) |
| void | getParam (std::string name, btTransform &t) |
| void | getParam (std::string name, btQuaternion &quat) |
| void | getParam (std::string name, btVector3 &vec) |
| void | getParam (std::string name, double &data) |
| double | getParam (std::string name) |
| 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, const Eigen::MatrixXd &mat, int type) |
| void | setParam (std::string name, const Eigen::VectorXd &vec, int type) |
| void | setParam (std::string name, const btTransform &t, int type) |
| void | setParam (std::string name, const btQuaternion &quat, int type) |
| void | setParam (std::string name, const btVector3 &vec, int type) |
| void | setParam (std::string name, double value, 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 |
Definition at line 19 of file generic_model.h.
| articulation_models::GenericModel::GenericModel | ( | ) |
Definition at line 32 of file generic_model.cpp.
| double articulation_models::GenericModel::evalLatestJacobian | ( | ) | [virtual] |
Definition at line 344 of file generic_model.cpp.
| bool articulation_models::GenericModel::evaluateModel | ( | ) | [virtual] |
Reimplemented in articulation_models::PCAGPModel.
Definition at line 279 of file generic_model.cpp.
| bool articulation_models::GenericModel::fitMinMaxConfigurations | ( | ) | [virtual] |
Definition at line 271 of file generic_model.cpp.
| bool articulation_models::GenericModel::fitModel | ( | ) | [virtual] |
Reimplemented in articulation_models::PCAGPModel.
Definition at line 256 of file generic_model.cpp.
| double articulation_models::GenericModel::getBIC | ( | ) | [virtual] |
Definition at line 392 of file generic_model.cpp.
| V_Configuration articulation_models::GenericModel::getConfiguration | ( | size_t | index | ) | [virtual] |
Definition at line 469 of file generic_model.cpp.
| size_t articulation_models::GenericModel::getDOFs | ( | ) | [virtual] |
Reimplemented in articulation_models::PCAGPModel, articulation_models::PrismaticModel, articulation_models::RigidModel, and articulation_models::RotationalModel.
Definition at line 94 of file generic_model.cpp.
| int articulation_models::GenericModel::getId | ( | ) |
Definition at line 85 of file generic_model.cpp.
| double articulation_models::GenericModel::getInlierLogLikelihood | ( | size_t | index | ) | [virtual] |
Definition at line 604 of file generic_model.cpp.
| double articulation_models::GenericModel::getLogLikelihood | ( | bool | estimate_outlier_ratio | ) | [virtual] |
Definition at line 667 of file generic_model.cpp.
| double articulation_models::GenericModel::getLogLikelihoodForPoseIndex | ( | size_t | index | ) | [virtual] |
Definition at line 643 of file generic_model.cpp.
| V_Configuration articulation_models::GenericModel::getMaxConfigurationObserved | ( | ) | [virtual] |
Definition at line 511 of file generic_model.cpp.
| V_Configuration articulation_models::GenericModel::getMinConfigurationObserved | ( | ) | [virtual] |
Definition at line 494 of file generic_model.cpp.
| ModelMsg articulation_models::GenericModel::getModel | ( | ) | [virtual] |
Definition at line 62 of file generic_model.cpp.
| std::string articulation_models::GenericModel::getModelName | ( | ) | [virtual] |
Definition at line 90 of file generic_model.cpp.
| double articulation_models::GenericModel::getOrientationError | ( | ) | [virtual] |
Definition at line 388 of file generic_model.cpp.
| double articulation_models::GenericModel::getOutlierLogLikelihood | ( | ) | [virtual] |
Definition at line 626 of file generic_model.cpp.
| void articulation_models::GenericModel::getParam | ( | std::string | name, | |
| Eigen::MatrixXd & | mat | |||
| ) |
Definition at line 193 of file generic_model.cpp.
| void articulation_models::GenericModel::getParam | ( | std::string | name, | |
| Eigen::VectorXd & | vec | |||
| ) |
Definition at line 167 of file generic_model.cpp.
| void articulation_models::GenericModel::getParam | ( | std::string | name, | |
| btTransform & | t | |||
| ) |
Definition at line 185 of file generic_model.cpp.
| void articulation_models::GenericModel::getParam | ( | std::string | name, | |
| btQuaternion & | quat | |||
| ) |
Definition at line 178 of file generic_model.cpp.
| void articulation_models::GenericModel::getParam | ( | std::string | name, | |
| btVector3 & | vec | |||
| ) |
Definition at line 172 of file generic_model.cpp.
| void articulation_models::GenericModel::getParam | ( | std::string | name, | |
| double & | data | |||
| ) |
Definition at line 162 of file generic_model.cpp.
| double articulation_models::GenericModel::getParam | ( | std::string | name | ) |
Definition at line 152 of file generic_model.cpp.
| double articulation_models::GenericModel::getPositionError | ( | ) | [virtual] |
Definition at line 384 of file generic_model.cpp.
| size_t articulation_models::GenericModel::getSamples | ( | ) | [virtual] |
Definition at line 98 of file generic_model.cpp.
| TrackMsg articulation_models::GenericModel::getTrack | ( | ) | [virtual] |
Definition at line 77 of file generic_model.cpp.
| bool articulation_models::GenericModel::guessParameters | ( | ) | [virtual] |
Reimplemented in articulation_models::PrismaticModel, articulation_models::RigidModel, and articulation_models::RotationalModel.
Definition at line 711 of file generic_model.cpp.
| bool articulation_models::GenericModel::hasParam | ( | std::string | name | ) |
Definition at line 242 of file generic_model.cpp.
| void articulation_models::GenericModel::keepLatestPoseOnly | ( | ) | [virtual] |
Definition at line 593 of file generic_model.cpp.
| bool articulation_models::GenericModel::normalizeParameters | ( | ) | [virtual] |
Reimplemented in articulation_models::PCAGPModel, articulation_models::PrismaticModel, and articulation_models::RotationalModel.
Definition at line 876 of file generic_model.cpp.
| int articulation_models::GenericModel::openChannel | ( | std::string | name, | |
| bool | autocreate = true | |||
| ) | [virtual] |
Definition at line 251 of file generic_model.cpp.
| bool articulation_models::GenericModel::optimizeParameters | ( | ) | [virtual] |
Definition at line 790 of file generic_model.cpp.
| V_Configuration articulation_models::GenericModel::predictConfiguration | ( | geometry_msgs::Pose | pose | ) | [virtual] |
Reimplemented in articulation_models::PCAGPModel, articulation_models::PrismaticModel, and articulation_models::RotationalModel.
Definition at line 486 of file generic_model.cpp.
| M_CartesianJacobian articulation_models::GenericModel::predictHessian | ( | V_Configuration | q, | |
| double | delta = 1e-6 | |||
| ) | [virtual] |
Reimplemented in articulation_models::PrismaticModel.
Definition at line 415 of file generic_model.cpp.
| M_CartesianJacobian articulation_models::GenericModel::predictJacobian | ( | V_Configuration | q, | |
| double | delta = 1e-6 | |||
| ) | [virtual] |
Definition at line 403 of file generic_model.cpp.
| geometry_msgs::Pose articulation_models::GenericModel::predictPose | ( | V_Configuration | q | ) | [virtual] |
Reimplemented in articulation_models::PCAGPModel, articulation_models::PrismaticModel, articulation_models::RigidModel, and articulation_models::RotationalModel.
Definition at line 397 of file generic_model.cpp.
| void articulation_models::GenericModel::prepareChannels | ( | ) | [virtual] |
Definition at line 141 of file generic_model.cpp.
| void articulation_models::GenericModel::projectConfigurationToJacobian | ( | ) | [virtual] |
Reimplemented in articulation_models::PCAGPModel.
Definition at line 547 of file generic_model.cpp.
| void articulation_models::GenericModel::projectConfigurationToPose | ( | ) | [virtual] |
Reimplemented in articulation_models::PCAGPModel.
Definition at line 538 of file generic_model.cpp.
| void articulation_models::GenericModel::projectPoseToConfiguration | ( | ) | [virtual] |
Reimplemented in articulation_models::PCAGPModel.
Definition at line 529 of file generic_model.cpp.
| void articulation_models::GenericModel::readParamsFromModel | ( | ) | [virtual] |
Reimplemented in articulation_models::PCAGPModel, articulation_models::PrismaticModel, articulation_models::RigidModel, and articulation_models::RotationalModel.
Definition at line 103 of file generic_model.cpp.
| void articulation_models::GenericModel::sampleConfigurationSpace | ( | double | resolution | ) | [virtual] |
Definition at line 556 of file generic_model.cpp.
| bool articulation_models::GenericModel::sampleConsensus | ( | ) | [virtual] |
Definition at line 716 of file generic_model.cpp.
| void articulation_models::GenericModel::setConfiguration | ( | size_t | index, | |
| V_Configuration | q | |||
| ) | [virtual] |
Definition at line 442 of file generic_model.cpp.
| void articulation_models::GenericModel::setId | ( | int | id | ) |
Definition at line 81 of file generic_model.cpp.
| void articulation_models::GenericModel::setJacobian | ( | size_t | index, | |
| M_CartesianJacobian | J | |||
| ) | [virtual] |
Definition at line 457 of file generic_model.cpp.
| virtual void articulation_models::GenericModel::setModel | ( | const articulation_msgs::ModelMsg & | model | ) | [virtual] |
| void articulation_models::GenericModel::setParam | ( | std::string | name, | |
| const Eigen::MatrixXd & | mat, | |||
| int | type | |||
| ) |
Definition at line 236 of file generic_model.cpp.
| void articulation_models::GenericModel::setParam | ( | std::string | name, | |
| const Eigen::VectorXd & | vec, | |||
| int | type | |||
| ) |
Definition at line 213 of file generic_model.cpp.
| void articulation_models::GenericModel::setParam | ( | std::string | name, | |
| const btTransform & | t, | |||
| int | type | |||
| ) |
Definition at line 231 of file generic_model.cpp.
| void articulation_models::GenericModel::setParam | ( | std::string | name, | |
| const btQuaternion & | quat, | |||
| int | type | |||
| ) |
Definition at line 224 of file generic_model.cpp.
| void articulation_models::GenericModel::setParam | ( | std::string | name, | |
| const btVector3 & | vec, | |||
| int | type | |||
| ) |
Definition at line 218 of file generic_model.cpp.
| void articulation_models::GenericModel::setParam | ( | std::string | name, | |
| double | value, | |||
| int | type | |||
| ) |
Definition at line 199 of file generic_model.cpp.
| virtual void articulation_models::GenericModel::setTrack | ( | const articulation_msgs::TrackMsg & | track | ) | [virtual] |
| void articulation_models::GenericModel::updateParameters | ( | std::vector< double > | delta | ) | [virtual] |
Reimplemented in articulation_models::PrismaticModel, articulation_models::RigidModel, and articulation_models::RotationalModel.
Definition at line 873 of file generic_model.cpp.
| void articulation_models::GenericModel::writeParamsToModel | ( | ) | [virtual] |
Reimplemented in articulation_models::PCAGPModel, articulation_models::PrismaticModel, articulation_models::RigidModel, and articulation_models::RotationalModel.
Definition at line 121 of file generic_model.cpp.
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.
| std::vector<int> articulation_models::GenericModel::channelConfiguration |
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.
| Eigen::MatrixXd articulation_models::GenericModel::hessian |
Definition at line 37 of file generic_model.h.
| Eigen::MatrixXd articulation_models::GenericModel::jacobian |
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.
| articulation_msgs::ModelMsg articulation_models::GenericModel::model |
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.
| std::vector<articulation_msgs::ParamMsg> articulation_models::GenericModel::params_initial |
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.