45 :
JointModel(name, joint_index, first_variable_index), axis_(0.0, 0.0, 0.0)
70 if (bounds[0].min_position_ <= 0.0 && bounds[0].max_position_ >= 0.0)
76 values[0] = (bounds[0].min_position_ + bounds[0].max_position_) / 2.0;
82 return values[0] >= bounds[0].min_position_ - margin && values[0] <= bounds[0].max_position_ + margin;
86 const Bounds& bounds)
const
88 values[0] = rng.uniformReal(bounds[0].min_position_, bounds[0].max_position_);
92 const Bounds& bounds,
const double* near,
93 const double distance)
const
95 values[0] = rng.uniformReal(std::max(bounds[0].min_position_, near[0] -
distance),
96 std::min(bounds[0].max_position_, near[0] +
distance));
101 if (values[0] < bounds[0].min_position_)
103 values[0] = bounds[0].min_position_;
106 else if (values[0] > bounds[0].max_position_)
108 values[0] = bounds[0].max_position_;
116 return fabs(values1[0] - values2[0]);
121 state[0] = from[0] + (to[0] - from[0]) * t;
126 double* d = transf.data();
142 d[12] =
axis_.x() * joint_values[0];
143 d[13] =
axis_.y() * joint_values[0];
144 d[14] =
axis_.z() * joint_values[0];
153 joint_values[0] = transf.translation().dot(
axis_);
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
VariableIndexMap variable_index_map_
Map from variable names to the corresponding index in variable_names_ (indexing makes sense within th...
JointType type_
The type of joint.
Bounds variable_bounds_
The bounds for each variable (low, high) in the same order as variable_names_.
std::vector< VariableBounds > Bounds
The datatype for the joint bounds.
const std::string & getName() const
Get the name of the joint.
void computeVariableBoundsMsg()
double getMaximumExtent() const
std::vector< std::string > variable_names_
The full names to use for the variables that make up this joint.
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 ...
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,...
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 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 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 ...
Eigen::Vector3d axis_
The axis of the joint.
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 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 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)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW PrismaticJointModel(const std::string &name, size_t joint_index, size_t first_variable_index)
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,...
Main namespace for MoveIt.