39 #include <boost/math/constants/constants.hpp> 50 , axis_(0.0, 0.0, 0.0)
76 axis_ = axis.normalized();
107 if (bounds[0].min_position_ <= 0.0 && bounds[0].max_position_ >= 0.0)
110 values[0] = (bounds[0].min_position_ + bounds[0].max_position_) / 2.0;
114 const Bounds& bounds)
const 116 values[0] = rng.
uniformReal(bounds[0].min_position_, bounds[0].max_position_);
120 const Bounds& bounds,
const double* near,
125 values[0] = rng.
uniformReal(near[0] - distance, near[0] + distance);
129 values[0] = rng.
uniformReal(std::max(bounds[0].min_position_, near[0] - distance),
130 std::min(bounds[0].max_position_, near[0] + distance));
137 double diff = to[0] - from[0];
138 if (fabs(diff) <= boost::math::constants::pi<double>())
139 state[0] = from[0] + diff * t;
143 diff = 2.0 * boost::math::constants::pi<double>() - diff;
145 diff = -2.0 * boost::math::constants::pi<double>() - diff;
146 state[0] = from[0] - diff * t;
148 if (state[0] > boost::math::constants::pi<double>())
149 state[0] -= 2.0 * boost::math::constants::pi<double>();
150 else if (state[0] < -boost::math::constants::pi<double>())
151 state[0] += 2.0 * boost::math::constants::pi<double>();
155 state[0] = from[0] + (to[0] - from[0]) * t;
162 double d = fmod(fabs(values1[0] - values2[0]), 2.0 * boost::math::constants::pi<double>());
163 return (d > boost::math::constants::pi<double>()) ? 2.0 * boost::math::constants::pi<double>() - d : d;
166 return fabs(values1[0] - values2[0]);
174 return !(values[0] < bounds[0].min_position_ - margin || values[0] > bounds[0].max_position_ + margin);
181 double& v = values[0];
182 if (v <= -boost::math::constants::pi<double>() || v > boost::math::constants::pi<double>())
184 v = fmod(v, 2.0 * boost::math::constants::pi<double>());
185 if (v <= -boost::math::constants::pi<double>())
186 v += 2.0 * boost::math::constants::pi<double>();
187 else if (v > boost::math::constants::pi<double>())
188 v -= 2.0 * boost::math::constants::pi<double>();
194 if (values[0] < bounds[0].min_position_)
196 values[0] = bounds[0].min_position_;
199 else if (values[0] > bounds[0].max_position_)
201 values[0] = bounds[0].max_position_;
210 const double c =
cos(joint_values[0]);
211 const double s =
sin(joint_values[0]);
212 const double t = 1.0 - c;
213 const double txy = t *
xy_;
214 const double txz = t *
xz_;
215 const double tyz = t *
yz_;
217 const double zs =
axis_.z() * s;
218 const double ys =
axis_.y() * s;
219 const double xs =
axis_.x() * s;
222 double*
d = transf.data();
249 Eigen::Quaterniond q(transf.linear());
252 axis_.array().abs().maxCoeff(&maxIdx);
253 joint_values[0] = 2. *
atan2(q.vec()[maxIdx] /
axis_[maxIdx], q.w());
void setContinuous(bool flag)
bool continuous_
Flag indicating whether this joint wraps around.
std::string name_
Name of the joint.
virtual unsigned int getStateSpaceDimension() const
Get the dimension of the state space that corresponds to this joint.
Bounds variable_bounds_
The bounds for each variable (low, high) in the same order as variable_names_.
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 ...
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
virtual void computeVariablePositions(const Eigen::Affine3d &transf, double *joint_values) const
Given the transform generated by joint, compute the corresponding joint values.
JointType type_
The type of joint.
double getMaximumExtent() const
EIGEN_MAKE_ALIGNED_OPERATOR_NEW RevoluteJointModel(const std::string &name)
void computeVariableBoundsMsg()
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.
void setAxis(const Eigen::Vector3d &axis)
Set the axis of rotation.
double uniformReal(double lower_bound, double upper_bound)
VariableIndexMap variable_index_map_
Map from variable names to the corresponding index in variable_names_ (indexing makes sense within th...
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.
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...
std::vector< std::string > variable_names_
The full names to use for the variables that make up this joint.
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
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...
Main namespace for MoveIt!
virtual void computeTransform(const double *joint_values, Eigen::Affine3d &transf) const
Given the joint values for a joint, compute the corresponding transform.
Eigen::Vector3d axis_
The axis of the joint.
std::vector< VariableBounds > Bounds
The datatype for the joint bounds.
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
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 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 ...