Public Member Functions | Protected Attributes | Private Attributes
moveit::core::RevoluteJointModel Class Reference

A revolute joint. More...

#include <revolute_joint_model.h>

Inheritance diagram for moveit::core::RevoluteJointModel:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual void computeTransform (const double *joint_values, Eigen::Affine3d &transf) const
 Given the joint values for a joint, compute the corresponding transform.
virtual void computeVariablePositions (const Eigen::Affine3d &transf, double *joint_values) const
 Given the transform generated by joint, compute the corresponding joint values.
virtual double distance (const double *values1, const double *values2) const
 Compute the distance between two joint states of the same model (represented by the variable values)
virtual bool enforcePositionBounds (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. Return true if changes were made.
const Eigen::Vector3d & getAxis () const
 Get the axis of rotation.
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 getVariableDefaultPositions (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. Enough memory is assumed to be allocated.
virtual void getVariableRandomPositions (random_numbers::RandomNumberGenerator &rng, double *values, const Bounds &other_bounds) const
 Provide random values for the joint variables (within specified bounds). Enough memory is assumed to be allocated.
virtual void getVariableRandomPositionsNearBy (random_numbers::RandomNumberGenerator &rng, double *values, const Bounds &other_bounds, const double *near, const double distance) const
 Provide random values for the joint variables (within specified bounds). Enough memory is assumed to be allocated.
virtual void interpolate (const double *from, const double *to, const double t, 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.
bool isContinuous () const
 Check if this joint wraps around.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW RevoluteJointModel (const std::string &name)
virtual bool satisfiesPositionBounds (const double *values, const Bounds &other_bounds, double margin) const
 Check if the set of position values for the variables of this joint are within bounds, up to some margin.
void setAxis (const Eigen::Vector3d &axis)
 Set the axis of rotation.
void setContinuous (bool flag)

Protected Attributes

Eigen::Vector3d axis_
 The axis of the joint.
bool continuous_
 Flag indicating whether this joint wraps around.

Private Attributes

double x2_
double xy_
double xz_
double y2_
double yz_
double z2_

Detailed Description

A revolute joint.

Definition at line 48 of file revolute_joint_model.h.


Constructor & Destructor Documentation

Definition at line 44 of file revolute_joint_model.cpp.


Member Function Documentation

void moveit::core::RevoluteJointModel::computeTransform ( const double *  joint_values,
Eigen::Affine3d &  transf 
) const [virtual]

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

Implements moveit::core::JointModel.

Definition at line 204 of file revolute_joint_model.cpp.

void moveit::core::RevoluteJointModel::computeVariablePositions ( const Eigen::Affine3d &  transform,
double *  joint_values 
) const [virtual]

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

Implements moveit::core::JointModel.

Definition at line 243 of file revolute_joint_model.cpp.

double moveit::core::RevoluteJointModel::distance ( const double *  value1,
const double *  value2 
) const [virtual]

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

Implements moveit::core::JointModel.

Definition at line 153 of file revolute_joint_model.cpp.

bool moveit::core::RevoluteJointModel::enforcePositionBounds ( 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. Return true if changes were made.

Implements moveit::core::JointModel.

Definition at line 171 of file revolute_joint_model.cpp.

const Eigen::Vector3d& moveit::core::RevoluteJointModel::getAxis ( ) const [inline]

Get the axis of rotation.

Definition at line 78 of file revolute_joint_model.h.

double moveit::core::RevoluteJointModel::getMaximumExtent ( const Bounds other_bounds) const [virtual]

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

Implements moveit::core::JointModel.

Definition at line 95 of file revolute_joint_model.cpp.

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

Implements moveit::core::JointModel.

Definition at line 65 of file revolute_joint_model.cpp.

void moveit::core::RevoluteJointModel::getVariableDefaultPositions ( 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. Enough memory is assumed to be allocated.

Implements moveit::core::JointModel.

Definition at line 100 of file revolute_joint_model.cpp.

void moveit::core::RevoluteJointModel::getVariableRandomPositions ( random_numbers::RandomNumberGenerator rng,
double *  values,
const Bounds other_bounds 
) const [virtual]

Provide random values for the joint variables (within specified bounds). Enough memory is assumed to be allocated.

Implements moveit::core::JointModel.

Definition at line 109 of file revolute_joint_model.cpp.

void moveit::core::RevoluteJointModel::getVariableRandomPositionsNearBy ( random_numbers::RandomNumberGenerator rng,
double *  values,
const Bounds other_bounds,
const double *  near,
const double  distance 
) const [virtual]

Provide random values for the joint variables (within specified bounds). Enough memory is assumed to be allocated.

Implements moveit::core::JointModel.

Definition at line 114 of file revolute_joint_model.cpp.

void moveit::core::RevoluteJointModel::interpolate ( const double *  from,
const double *  to,
const double  t,
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 moveit::core::JointModel.

Definition at line 127 of file revolute_joint_model.cpp.

Check if this joint wraps around.

Definition at line 72 of file revolute_joint_model.h.

bool moveit::core::RevoluteJointModel::satisfiesPositionBounds ( const double *  values,
const Bounds other_bounds,
double  margin 
) const [virtual]

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

Implements moveit::core::JointModel.

Definition at line 164 of file revolute_joint_model.cpp.

void moveit::core::RevoluteJointModel::setAxis ( const Eigen::Vector3d &  axis)

Set the axis of rotation.

Definition at line 70 of file revolute_joint_model.cpp.

Definition at line 81 of file revolute_joint_model.cpp.


Member Data Documentation

Eigen::Vector3d moveit::core::RevoluteJointModel::axis_ [protected]

The axis of the joint.

Definition at line 89 of file revolute_joint_model.h.

Flag indicating whether this joint wraps around.

Definition at line 92 of file revolute_joint_model.h.

Definition at line 96 of file revolute_joint_model.h.

Definition at line 96 of file revolute_joint_model.h.

Definition at line 96 of file revolute_joint_model.h.

Definition at line 96 of file revolute_joint_model.h.

Definition at line 96 of file revolute_joint_model.h.

Definition at line 96 of file revolute_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 Thu Aug 27 2015 13:58:54