Public Member Functions | Protected Attributes | Friends
robot_model::PrismaticJointModel Class Reference

A prismatic joint. More...

#include <prismatic_joint_model.h>

Inheritance diagram for robot_model::PrismaticJointModel:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual void computeJointStateValues (const Eigen::Affine3d &transf, std::vector< double > &joint_values) const
 Given the transform generated by joint, compute the corresponding joint values.
virtual void computeTransform (const std::vector< double > &joint_values, Eigen::Affine3d &transf) const
 Given the joint values for a joint, compute the corresponding transform.
virtual double distance (const std::vector< double > &values1, const std::vector< double > &values2) const
 Compute the distance between two joint states of the same model (represented by the variable values)
virtual void enforceBounds (std::vector< double > &values, const Bounds &other_bounds) const
 Force the specified values to be inside bounds and normalized. Quaternions are normalized, continuous joints are made between -Pi and Pi.
const Eigen::Vector3d & getAxis () const
 Get the axis of translation.
virtual double getMaximumExtent (const Bounds &other_bounds) const
 Get the extent of the state space (the maximum value distance() can ever report)
virtual unsigned int getStateSpaceDimension () const
 Get the dimension of the state space that corresponds to this joint.
virtual void getVariableDefaultValues (std::vector< double > &values, const Bounds &other_bounds) const
 Provide a default value for the joint given the joint variable bounds. Most joints will use the default implementation provided in this base class, but the quaternion for example needs a different implementation. The vector is NOT cleared; elements are only added with push_back.
virtual void getVariableRandomValues (random_numbers::RandomNumberGenerator &rng, std::vector< double > &values, const Bounds &other_bounds) const
 Provide random values for the joint variables (within specified bounds). The vector is NOT cleared; elements are only added with push_back.
virtual void getVariableRandomValuesNearBy (random_numbers::RandomNumberGenerator &rng, std::vector< double > &values, const Bounds &other_bounds, const std::vector< double > &near, const double distance) const
 Provide random values for the joint variables (within specified bounds). The vector is NOT cleared; elements are only added with push_back.
virtual void interpolate (const std::vector< double > &from, const std::vector< double > &to, const double t, std::vector< double > &state) const
 Computes the state that lies at time t in [0, 1] on the segment that connects from state to to state. The memory location of state is not required to be different from the memory of either from or to.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW PrismaticJointModel (const std::string &name)
virtual bool satisfiesBounds (const std::vector< double > &values, const Bounds &other_bounds, double margin) const
 Check if the set of values for the variables of this joint are within bounds, up to some margin.
virtual void updateTransform (const std::vector< double > &joint_values, Eigen::Affine3d &transf) const
 Update a transform so that it corresponds to the new joint values assuming that transf was previously set to identity and that only calls to updateTransform() were issued afterwards.

Protected Attributes

Eigen::Vector3d axis_
 The axis of the joint.

Friends

class RobotModel

Detailed Description

A prismatic joint.

Definition at line 46 of file prismatic_joint_model.h.


Constructor & Destructor Documentation

Definition at line 40 of file prismatic_joint_model.cpp.


Member Function Documentation

void robot_model::PrismaticJointModel::computeJointStateValues ( const Eigen::Affine3d &  transform,
std::vector< double > &  joint_values 
) const [virtual]

Given the transform generated by joint, compute the corresponding joint values.

Implements robot_model::JointModel.

Definition at line 119 of file prismatic_joint_model.cpp.

void robot_model::PrismaticJointModel::computeTransform ( const std::vector< double > &  joint_values,
Eigen::Affine3d &  transf 
) const [virtual]

Given the joint values for a joint, compute the corresponding transform.

Implements robot_model::JointModel.

Definition at line 108 of file prismatic_joint_model.cpp.

double robot_model::PrismaticJointModel::distance ( const std::vector< double > &  values1,
const std::vector< double > &  values2 
) const [virtual]

Compute the distance between two joint states of the same model (represented by the variable values)

Implements robot_model::JointModel.

Definition at line 96 of file prismatic_joint_model.cpp.

void robot_model::PrismaticJointModel::enforceBounds ( std::vector< double > &  values,
const Bounds other_bounds 
) const [virtual]

Force the specified values to be inside bounds and normalized. Quaternions are normalized, continuous joints are made between -Pi and Pi.

Implements robot_model::JointModel.

Definition at line 86 of file prismatic_joint_model.cpp.

const Eigen::Vector3d& robot_model::PrismaticJointModel::getAxis ( ) const [inline]

Get the axis of translation.

Definition at line 69 of file prismatic_joint_model.h.

double robot_model::PrismaticJointModel::getMaximumExtent ( const Bounds other_bounds) const [virtual]

Get the extent of the state space (the maximum value distance() can ever report)

Implements robot_model::JointModel.

Definition at line 52 of file prismatic_joint_model.cpp.

Get the dimension of the state space that corresponds to this joint.

Implements robot_model::JointModel.

Definition at line 47 of file prismatic_joint_model.cpp.

void robot_model::PrismaticJointModel::getVariableDefaultValues ( std::vector< double > &  values,
const Bounds other_bounds 
) const [virtual]

Provide a default value for the joint given the joint variable bounds. Most joints will use the default implementation provided in this base class, but the quaternion for example needs a different implementation. The vector is NOT cleared; elements are only added with push_back.

Implements robot_model::JointModel.

Definition at line 57 of file prismatic_joint_model.cpp.

void robot_model::PrismaticJointModel::getVariableRandomValues ( random_numbers::RandomNumberGenerator rng,
std::vector< double > &  values,
const Bounds other_bounds 
) const [virtual]

Provide random values for the joint variables (within specified bounds). The vector is NOT cleared; elements are only added with push_back.

Implements robot_model::JointModel.

Definition at line 74 of file prismatic_joint_model.cpp.

void robot_model::PrismaticJointModel::getVariableRandomValuesNearBy ( random_numbers::RandomNumberGenerator rng,
std::vector< double > &  values,
const Bounds other_bounds,
const std::vector< double > &  near,
const double  distance 
) const [virtual]

Provide random values for the joint variables (within specified bounds). The vector is NOT cleared; elements are only added with push_back.

Implements robot_model::JointModel.

Definition at line 79 of file prismatic_joint_model.cpp.

void robot_model::PrismaticJointModel::interpolate ( const std::vector< double > &  from,
const std::vector< double > &  to,
const double  t,
std::vector< double > &  state 
) const [virtual]

Computes the state that lies at time t in [0, 1] on the segment that connects from state to to state. The memory location of state is not required to be different from the memory of either from or to.

Implements robot_model::JointModel.

Definition at line 103 of file prismatic_joint_model.cpp.

bool robot_model::PrismaticJointModel::satisfiesBounds ( const std::vector< double > &  values,
const Bounds other_bounds,
double  margin 
) const [virtual]

Check if the set of values for the variables of this joint are within bounds, up to some margin.

Implements robot_model::JointModel.

Definition at line 66 of file prismatic_joint_model.cpp.

void robot_model::PrismaticJointModel::updateTransform ( const std::vector< double > &  joint_values,
Eigen::Affine3d &  transf 
) const [virtual]

Update a transform so that it corresponds to the new joint values assuming that transf was previously set to identity and that only calls to updateTransform() were issued afterwards.

Implements robot_model::JointModel.

Definition at line 114 of file prismatic_joint_model.cpp.


Friends And Related Function Documentation

friend class RobotModel [friend]

Reimplemented from robot_model::JointModel.

Definition at line 48 of file prismatic_joint_model.h.


Member Data Documentation

Eigen::Vector3d robot_model::PrismaticJointModel::axis_ [protected]

The axis of the joint.

Definition at line 76 of file prismatic_joint_model.h.


The documentation for this class was generated from the following files:


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Mon Oct 6 2014 02:24:48