56 PlanarJointModel(
const std::string& name,
size_t joint_index,
size_t first_variable_index);
60 const Bounds& other_bounds)
const override;
62 const Bounds& other_bounds,
const double* near,
63 const double distance)
const override;
67 void interpolate(
const double* from,
const double* to,
const double t,
double* state)
const override;
70 double distance(
const double* values1,
const double* values2)
const override;
72 void computeTransform(
const double* joint_values, Eigen::Isometry3d& transf)
const override;
77 return angular_distance_weight_;
82 angular_distance_weight_ = weight;
87 return min_translational_distance_;
92 min_translational_distance_ = min_translational_distance;
102 motion_model_ = model;
111 double angular_distance_weight_;
114 double min_translational_distance_;
130 double& dx,
double& dy,
double& initial_turn,
double& drive_angle,
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
std::vector< VariableBounds > Bounds
The datatype for the joint bounds.
double getMaximumExtent() const
bool normalizeRotation(double *values) const
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....
void getVariableRandomPositionsNearBy(random_numbers::RandomNumberGenerator &rng, double *values, const Bounds &other_bounds, const double *near, const double distance) const override
Provide random values for the joint variables (within specified bounds). Enough memory is assumed to ...
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 setMinTranslationalDistance(double min_translational_distance)
void setMotionModel(MotionModel model)
double getMinTranslationalDistance() const
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...
void setAngularDistanceWeight(double weight)
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,...
MotionModel getMotionModel() const
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 ...
double getAngularDistanceWeight() const
unsigned int getStateSpaceDimension() const override
Get the dimension of the state space that corresponds to this joint.
bool enforcePositionBounds(double *values, const Bounds &other_bounds) const override
Force the specified values to be inside bounds and normalized. Quaternions are normalized,...
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...
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)
MotionModel
different types of planar joints we support
void computeTurnDriveTurnGeometry(const double *from, const double *to, const double min_translational_distance, double &dx, double &dy, double &initial_turn, double &drive_angle, double &final_turn)
Compute the geometry to turn toward the target point, drive straight and then turn to target orientat...
Main namespace for MoveIt.