37 #ifndef MOVEIT_CORE_ROBOT_MODEL_FLOATING_JOINT_MODEL_ 38 #define MOVEIT_CORE_ROBOT_MODEL_FLOATING_JOINT_MODEL_ 54 const Bounds& other_bounds)
const;
56 const Bounds& other_bounds,
const double* near,
61 virtual void interpolate(
const double* from,
const double* to,
const double t,
double* state)
const;
64 virtual double distance(
const double* values1,
const double* values2)
const;
66 virtual void computeTransform(
const double* joint_values, Eigen::Affine3d& transf)
const;
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.
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.
double distanceRotation(const double *values1, const double *values2) const
Get the distance between the rotation components of two states.
double distanceTranslation(const double *values1, const double *values2) const
Get the distance between the translation components of two states.
virtual void computeTransform(const double *joint_values, Eigen::Affine3d &transf) const
Given the joint values for a joint, compute the corresponding transform.
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 defau...
virtual unsigned int getStateSpaceDimension() const
Get the dimension of the state space that corresponds to this joint.
FloatingJointModel(const std::string &name)
double getMaximumExtent() const
virtual void computeVariablePositions(const Eigen::Affine3d &transf, double *joint_values) const
Given the transform generated by joint, compute the corresponding joint values.
double getAngularDistanceWeight() const
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 ...
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...
double angular_distance_weight_
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) ...
A joint from the robot. Models the transform that this joint applies in the kinematic chain...
void setAngularDistanceWeight(double weight)
Main namespace for MoveIt!
std::vector< VariableBounds > Bounds
The datatype for the joint bounds.
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 ...
bool normalizeRotation(double *values) const