Go to the documentation of this file.
46 class RevoluteJointModel :
public JointModel
49 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
54 const Bounds& other_bounds)
const override;
56 const Bounds& other_bounds,
const double* seed,
57 const double distance)
const override;
62 void interpolate(
const double* from,
const double* to,
const double t,
double* state)
const override;
65 double distance(
const double* values1,
const double* values2)
const override;
67 void computeTransform(
const double* joint_values, Eigen::Isometry3d& transf)
const override;
bool enforcePositionBounds(double *values, const Bounds &other_bounds) const override
Force the specified values to be inside bounds and normalized. Quaternions are normalized,...
void getVariableRandomPositions(random_numbers::RandomNumberGenerator &rng, double *values, const Bounds &other_bounds) const override
Provide random values for the joint variables (within specified bounds). Enough memory is assumed to ...
void setAxis(const Eigen::Vector3d &axis)
Set the axis of rotation.
void getVariableRandomPositionsNearBy(random_numbers::RandomNumberGenerator &rng, double *values, const Bounds &other_bounds, const double *seed, const double distance) const override
Provide random values for the joint variables (within specified bounds). Enough memory is assumed to ...
void computeTransform(const double *joint_values, Eigen::Isometry3d &transf) const override
Given the joint values for a joint, compute the corresponding transform. The computed transform is gu...
bool isContinuous() const
Check if this joint wraps around.
void getVariableDefaultPositions(double *values, const Bounds &other_bounds) const override
Provide a default value for the joint given the joint variable bounds. Most joints will use the defau...
void interpolate(const double *from, const double *to, const double t, double *state) const override
Computes the state that lies at time t in [0, 1] on the segment that connects from state to to state....
double getMaximumExtent() const
std::vector< VariableBounds > Bounds
The datatype for the joint bounds.
double distance(const double *values1, const double *values2) const override
Compute the distance between two joint states of the same model (represented by the variable values)
void computeVariablePositions(const Eigen::Isometry3d &transf, double *joint_values) const override
Given the transform generated by joint, compute the corresponding joint values. Make sure the passed ...
unsigned int getStateSpaceDimension() const override
Get the dimension of the state space that corresponds to this joint.
Main namespace for MoveIt.
bool harmonizePosition(double *values, const Bounds &other_bounds) const override
EIGEN_MAKE_ALIGNED_OPERATOR_NEW RevoluteJointModel(const std::string &name)
bool continuous_
Flag indicating whether this joint wraps around.
const Eigen::Vector3d & getAxis() const
Get the axis of rotation.
bool satisfiesPositionBounds(const double *values, const Bounds &other_bounds, double margin) const override
Check if the set of position values for the variables of this joint are within bounds,...
Eigen::Vector3d axis_
The axis of the joint.
void setContinuous(bool flag)
Vec3fX< details::Vec3Data< double > > Vector3d
moveit_core
Author(s): Ioan Sucan
, Sachin Chitta , Acorn Pooley
autogenerated on Thu Nov 21 2024 03:23:41