Public Member Functions
moveit::core::FixedJointModel Class Reference

A fixed joint. More...

#include <fixed_joint_model.h>

Inheritance diagram for moveit::core::FixedJointModel:
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.
 FixedJointModel (const std::string &name)
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.
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.

Detailed Description

A fixed joint.

Definition at line 47 of file fixed_joint_model.h.


Constructor & Destructor Documentation

moveit::core::FixedJointModel::FixedJointModel ( const std::string &  name)

Definition at line 39 of file fixed_joint_model.cpp.


Member Function Documentation

void moveit::core::FixedJointModel::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 90 of file fixed_joint_model.cpp.

void moveit::core::FixedJointModel::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 95 of file fixed_joint_model.cpp.

double moveit::core::FixedJointModel::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 75 of file fixed_joint_model.cpp.

bool moveit::core::FixedJointModel::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 64 of file fixed_joint_model.cpp.

double moveit::core::FixedJointModel::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 80 of file fixed_joint_model.cpp.

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

Implements moveit::core::JointModel.

Definition at line 44 of file fixed_joint_model.cpp.

void moveit::core::FixedJointModel::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 49 of file fixed_joint_model.cpp.

void moveit::core::FixedJointModel::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 53 of file fixed_joint_model.cpp.

void moveit::core::FixedJointModel::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 58 of file fixed_joint_model.cpp.

void moveit::core::FixedJointModel::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 85 of file fixed_joint_model.cpp.

bool moveit::core::FixedJointModel::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 69 of file fixed_joint_model.cpp.


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


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Wed Jun 19 2019 19:23:50