Namespaces | |
| namespace | track_utils |
| namespace | transform_datatypes |
Classes | |
| class | GenericModel |
| class | GenericModelFactory |
| class | MultiModelFactory |
| class | PCAGPModel |
| class | PrismaticModel |
| class | RigidModel |
| class | RotationalModel |
| class | SingleModelFactory |
Typedefs | |
| typedef boost::shared_ptr < GenericModel const > | GenericModelConstPtr |
| typedef boost::shared_ptr < GenericModel > | GenericModelPtr |
| typedef std::vector < GenericModelPtr > | GenericModelVector |
| typedef Eigen::MatrixXd | M_CartesianJacobian |
| typedef Eigen::VectorXd | V_Configuration |
Functions | |
| bool | check_values (float v) |
| bool | check_values (double v) |
| bool | check_values (const btQuaternion &vec) |
| bool | check_values (const btVector3 &vec) |
| geometry_msgs::Point | eigenToPoint (Eigen::VectorXd v) |
| articulation_msgs::TrackMsg | flipTrack (articulation_msgs::TrackMsg input, int corner=0) |
| double | getParam (std::vector< articulation_msgs::ParamMsg > &vec, std::string name) |
| bool | hasParam (std::vector< articulation_msgs::ParamMsg > &vec, std::string name) |
| void | my_df (const gsl_vector *v, void *params, gsl_vector *df) |
| double | my_f (const gsl_vector *v, void *params) |
| void | my_fdf (const gsl_vector *x, void *params, double *f, gsl_vector *df) |
| int | openChannel (articulation_msgs::TrackMsg &track, std::string name, bool autocreate=true) |
| btQuaternion | orientationToQuaternion (geometry_msgs::Quaternion orientation) |
| Eigen::VectorXd | pointToEigen (geometry_msgs::Point p) |
| btTransform | poseToTransform (geometry_msgs::Pose pose) |
| btVector3 | positionToVector (geometry_msgs::Point position) |
| geometry_msgs::Quaternion | quaternionToOrientation (btQuaternion quat) |
| void | readParamsFromModel () |
| void | setParam (std::vector< articulation_msgs::ParamMsg > &vec, std::string name, double value, uint8_t type=articulation_msgs::ParamMsg::PRIOR) |
| void | setParamIfNotDefined (std::vector< articulation_msgs::ParamMsg > &vec, std::string name, double value, uint8_t type=articulation_msgs::ParamMsg::PRIOR) |
| geometry_msgs::Pose | transformToPose (btTransform transform) |
| geometry_msgs::Point | vectorToPosition (btVector3 point) |
| void | writeParamsToModel () |
| typedef boost::shared_ptr<GenericModel const> articulation_models::GenericModelConstPtr |
Definition at line 123 of file generic_model.h.
| typedef boost::shared_ptr< GenericModel > articulation_models::GenericModelPtr |
| typedef std::vector< GenericModelPtr > articulation_models::GenericModelVector |
| typedef Eigen::MatrixXd articulation_models::M_CartesianJacobian |
| typedef Eigen::VectorXd articulation_models::V_Configuration |
| bool articulation_models::check_values | ( | const btQuaternion & | vec | ) |
| bool articulation_models::check_values | ( | const btVector3 & | vec | ) |
| geometry_msgs::Point articulation_models::eigenToPoint | ( | Eigen::VectorXd | v | ) |
| articulation_msgs::TrackMsg articulation_models::flipTrack | ( | articulation_msgs::TrackMsg | input, | |
| int | corner = 0 | |||
| ) |
| double articulation_models::getParam | ( | std::vector< articulation_msgs::ParamMsg > & | vec, | |
| std::string | name | |||
| ) |
| bool articulation_models::hasParam | ( | std::vector< articulation_msgs::ParamMsg > & | vec, | |
| std::string | name | |||
| ) |
| void articulation_models::my_df | ( | const gsl_vector * | v, | |
| void * | params, | |||
| gsl_vector * | df | |||
| ) |
Definition at line 762 of file generic_model.cpp.
| double articulation_models::my_f | ( | const gsl_vector * | v, | |
| void * | params | |||
| ) |
Definition at line 741 of file generic_model.cpp.
| void articulation_models::my_fdf | ( | const gsl_vector * | x, | |
| void * | params, | |||
| double * | f, | |||
| gsl_vector * | df | |||
| ) |
Definition at line 783 of file generic_model.cpp.
| int articulation_models::openChannel | ( | articulation_msgs::TrackMsg & | track, | |
| std::string | name, | |||
| bool | autocreate = true | |||
| ) |
| btQuaternion articulation_models::orientationToQuaternion | ( | geometry_msgs::Quaternion | orientation | ) | [inline] |
| Eigen::VectorXd articulation_models::pointToEigen | ( | geometry_msgs::Point | p | ) |
| btTransform articulation_models::poseToTransform | ( | geometry_msgs::Pose | pose | ) | [inline] |
| btVector3 articulation_models::positionToVector | ( | geometry_msgs::Point | position | ) | [inline] |
| geometry_msgs::Quaternion articulation_models::quaternionToOrientation | ( | btQuaternion | quat | ) | [inline] |
| void articulation_models::readParamsFromModel | ( | ) |
| void articulation_models::setParam | ( | std::vector< articulation_msgs::ParamMsg > & | vec, | |
| std::string | name, | |||
| double | value, | |||
| uint8_t | type = articulation_msgs::ParamMsg::PRIOR | |||
| ) |
| void articulation_models::setParamIfNotDefined | ( | std::vector< articulation_msgs::ParamMsg > & | vec, | |
| std::string | name, | |||
| double | value, | |||
| uint8_t | type = articulation_msgs::ParamMsg::PRIOR | |||
| ) |
| geometry_msgs::Pose articulation_models::transformToPose | ( | btTransform | transform | ) | [inline] |
| geometry_msgs::Point articulation_models::vectorToPosition | ( | btVector3 | point | ) | [inline] |
| void articulation_models::writeParamsToModel | ( | ) |