39#include <geometric_shapes/check_isometry.h>
48 :
JointModel(name, joint_index, first_variable_index)
49 , axis_(0.0, 0.0, 0.0)
75 axis_ = axis.normalized();
106 if (bounds[0].min_position_ <= 0.0 && bounds[0].max_position_ >= 0.0)
112 values[0] = (bounds[0].min_position_ + bounds[0].max_position_) / 2.0;
117 const Bounds& bounds)
const
119 values[0] = rng.uniformReal(bounds[0].min_position_, bounds[0].max_position_);
123 const Bounds& bounds,
const double* near,
124 const double distance)
const
133 values[0] = rng.uniformReal(std::max(bounds[0].min_position_, near[0] -
distance),
134 std::min(bounds[0].max_position_, near[0] +
distance));
142 double diff = to[0] - from[0];
143 if (fabs(diff) <= M_PI)
145 state[0] = from[0] + diff * t;
151 diff = 2.0 * M_PI - diff;
155 diff = -2.0 * M_PI - diff;
157 state[0] = from[0] - diff * t;
161 state[0] -= 2.0 * M_PI;
163 else if (state[0] < -M_PI)
165 state[0] += 2.0 * M_PI;
170 state[0] = from[0] + (to[0] - from[0]) * t;
177 double d = fmod(fabs(values1[0] - values2[0]), 2.0 * M_PI);
178 return (d > M_PI) ? 2.0 * M_PI - d : d;
181 return fabs(values1[0] - values2[0]);
192 return values[0] >= bounds[0].min_position_ - margin && values[0] <= bounds[0].max_position_ + margin;
198 bool modified =
false;
199 if (*values < other_bounds[0].min_position_)
201 while (*values + 2 * M_PI <= other_bounds[0].max_position_)
207 else if (*values > other_bounds[0].max_position_)
209 while (*values - 2 * M_PI >= other_bounds[0].min_position_)
222 double& v = values[0];
223 if (v <= -M_PI || v > M_PI)
225 v = fmod(v, 2.0 * M_PI);
238 if (values[0] < bounds[0].min_position_)
240 values[0] = bounds[0].min_position_;
242 else if (values[0] > bounds[0].max_position_)
244 values[0] = bounds[0].max_position_;
252 const double c = cos(joint_values[0]);
253 const double s = sin(joint_values[0]);
254 const double t = 1.0 - c;
255 const double txy = t * xy_;
256 const double txz = t * xz_;
257 const double tyz = t * yz_;
259 const double zs =
axis_.z() * s;
260 const double ys =
axis_.y() * s;
261 const double xs =
axis_.x() * s;
264 double* d = transf.data();
291 ASSERT_ISOMETRY(transf)
292 Eigen::Quaterniond q(transf.linear());
295 axis_.array().abs().maxCoeff(&max_idx);
296 joint_values[0] = 2. * atan2(q.vec()[max_idx] /
axis_[max_idx], q.w());
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 continuous_
Flag indicating whether this joint wraps around.
Eigen::Vector3d axis_
The axis of the joint.
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 ...
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...
unsigned int getStateSpaceDimension() const override
Get the dimension of the state space that corresponds to this joint.
bool harmonizePosition(double *values, const Bounds &other_bounds) const override
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...
EIGEN_MAKE_ALIGNED_OPERATOR_NEW RevoluteJointModel(const std::string &name, size_t joint_index, size_t first_variable_index)
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 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 setAxis(const Eigen::Vector3d &axis)
Set the axis of rotation.
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 ...
bool enforcePositionBounds(double *values, const Bounds &other_bounds) const override
Force the specified values to be inside bounds and normalized. Quaternions are normalized,...
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 setContinuous(bool flag)
Main namespace for MoveIt.