39 #include <boost/math/constants/constants.hpp> 58 for (
int i = 0; i < 7; ++i)
74 variable_bounds_[0].min_position_ = -std::numeric_limits<double>::infinity();
76 variable_bounds_[1].min_position_ = -std::numeric_limits<double>::infinity();
78 variable_bounds_[2].min_position_ = -std::numeric_limits<double>::infinity();
94 double dx = other_bounds[0].max_position_ - other_bounds[0].min_position_;
95 double dy = other_bounds[1].max_position_ - other_bounds[1].min_position_;
96 double dz = other_bounds[2].max_position_ - other_bounds[2].min_position_;
107 double dx = values1[0] - values2[0];
108 double dy = values1[1] - values2[1];
109 double dz = values1[2] - values2[2];
110 return sqrt(dx * dx + dy * dy + dz * dz);
116 fabs(values1[3] * values2[3] + values1[4] * values2[4] + values1[5] * values2[5] + values1[6] * values2[6]);
117 if (dq + std::numeric_limits<double>::epsilon() >= 1.0)
126 state[0] = from[0] + (to[0] - from[0]) * t;
127 state[1] = from[1] + (to[1] - from[1]) * t;
128 state[2] = from[2] + (to[2] - from[2]) * t;
130 double dq = fabs(from[3] * to[3] + from[4] * to[4] + from[5] * to[5] + from[6] * to[6]);
131 double theta = (dq + std::numeric_limits<double>::epsilon() >= 1.0) ? 0.0 :
acos(dq);
132 if (theta > std::numeric_limits<double>::epsilon())
134 double d = 1.0 /
sin(theta);
135 double s0 =
sin((1.0 - t) * theta);
136 double s1 =
sin(t * theta);
139 state[3] = (from[3] * s0 + to[3] * s1) * d;
140 state[4] = (from[4] * s0 + to[4] * s1) * d;
141 state[5] = (from[5] * s0 + to[5] * s1) * d;
142 state[6] = (from[6] * s0 + to[6] * s1) * d;
155 if (values[0] < bounds[0].min_position_ - margin || values[0] > bounds[0].max_position_ + margin)
157 if (values[1] < bounds[1].min_position_ - margin || values[1] > bounds[1].max_position_ + margin)
159 if (values[2] < bounds[2].min_position_ - margin || values[2] > bounds[2].max_position_ + margin)
161 double normSqr = values[3] * values[3] + values[4] * values[4] + values[5] * values[5] + values[6] * values[6];
162 return fabs(normSqr - 1.0) <= std::numeric_limits<float>::epsilon() * 10.0;
168 double normSqr = values[3] * values[3] + values[4] * values[4] + values[5] * values[5] + values[6] * values[6];
169 if (fabs(normSqr - 1.0) > std::numeric_limits<double>::epsilon() * 100.0)
171 double norm =
sqrt(normSqr);
172 if (norm < std::numeric_limits<double>::epsilon() * 100.0)
174 ROS_WARN_NAMED(
"robot_model",
"Quaternion is zero in RobotState representation. Setting to identity");
201 for (
unsigned int i = 0; i < 3; ++i)
203 if (values[i] < bounds[i].min_position_)
205 values[i] = bounds[i].min_position_;
208 else if (values[i] > bounds[i].max_position_)
210 values[i] = bounds[i].max_position_;
219 transf = Eigen::Affine3d(
220 Eigen::Translation3d(joint_values[0], joint_values[1], joint_values[2]) *
221 Eigen::Quaterniond(joint_values[6], joint_values[3], joint_values[4], joint_values[5]).toRotationMatrix());
226 joint_values[0] = transf.translation().x();
227 joint_values[1] = transf.translation().y();
228 joint_values[2] = transf.translation().z();
229 Eigen::Quaterniond q(transf.linear());
230 joint_values[3] = q.x();
231 joint_values[4] = q.y();
232 joint_values[5] = q.z();
233 joint_values[6] = q.w();
238 for (
unsigned int i = 0; i < 3; ++i)
241 if (bounds[i].min_position_ <= 0.0 && bounds[i].max_position_ >= 0.0)
244 values[i] = (bounds[i].min_position_ + bounds[i].max_position_) / 2.0;
254 const Bounds& bounds)
const 256 if (bounds[0].max_position_ >= std::numeric_limits<double>::infinity() ||
257 bounds[0].min_position_ <= -std::numeric_limits<double>::infinity())
260 values[0] = rng.
uniformReal(bounds[0].min_position_, bounds[0].max_position_);
261 if (bounds[1].max_position_ >= std::numeric_limits<double>::infinity() ||
262 bounds[1].min_position_ <= -std::numeric_limits<double>::infinity())
265 values[1] = rng.
uniformReal(bounds[1].min_position_, bounds[1].max_position_);
266 if (bounds[2].max_position_ >= std::numeric_limits<double>::infinity() ||
267 bounds[2].min_position_ <= -std::numeric_limits<double>::infinity())
270 values[2] = rng.
uniformReal(bounds[2].min_position_, bounds[2].max_position_);
281 const Bounds& bounds,
const double* near,
284 if (bounds[0].max_position_ >= std::numeric_limits<double>::infinity() ||
285 bounds[0].min_position_ <= -std::numeric_limits<double>::infinity())
288 values[0] = rng.
uniformReal(std::max(bounds[0].min_position_, near[0] - distance),
289 std::min(bounds[0].max_position_, near[0] + distance));
290 if (bounds[1].max_position_ >= std::numeric_limits<double>::infinity() ||
291 bounds[1].min_position_ <= -std::numeric_limits<double>::infinity())
294 values[1] = rng.
uniformReal(std::max(bounds[1].min_position_, near[1] - distance),
295 std::min(bounds[1].max_position_, near[1] + distance));
296 if (bounds[2].max_position_ >= std::numeric_limits<double>::infinity() ||
297 bounds[2].min_position_ <= -std::numeric_limits<double>::infinity())
300 values[2] = rng.
uniformReal(std::max(bounds[2].min_position_, near[2] - distance),
301 std::min(bounds[2].max_position_, near[2] + distance));
304 if (da >= .25 * boost::math::constants::pi<double>())
320 double angle = 2.0 *
pow(rng.
uniform01(), 1.0 / 3.0) * da;
323 double norm =
sqrt(ax * ax + ay * ay + az * az);
326 q[0] = q[1] = q[2] = 0.0;
331 double s =
sin(angle / 2.0);
332 q[0] = s * ax / norm;
333 q[1] = s * ay / norm;
334 q[2] = s * az / norm;
335 q[3] =
cos(angle / 2.0);
338 values[3] = near[6] * q[0] + near[3] * q[3] + near[4] * q[2] - near[5] * q[1];
339 values[4] = near[6] * q[1] + near[4] * q[3] + near[5] * q[0] - near[3] * q[2];
340 values[5] = near[6] * q[2] + near[5] * q[3] + near[3] * q[1] - near[4] * q[0];
341 values[6] = near[6] * q[3] - near[3] * q[0] - near[4] * q[1] - near[5] * q[2];
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.
std::vector< std::string > local_variable_names_
The local names to use for the variables that make up this joint.
#define ROS_WARN_NAMED(name,...)
double distanceTranslation(const double *values1, const double *values2) const
Get the distance between the translation components of two states.
void quaternion(double value[4])
std::string name_
Name of the joint.
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.
Bounds variable_bounds_
The bounds for each variable (low, high) in the same order as variable_names_.
FloatingJointModel(const std::string &name)
JointType type_
The type of joint.
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.
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 ...
void computeVariableBoundsMsg()
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_
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...
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
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...
INLINE Rall1d< T, V, S > pow(const Rall1d< T, V, S > &arg, double m)
INLINE Rall1d< T, V, S > acos(const Rall1d< T, V, S > &x)
std::vector< std::string > variable_names_
The full names to use for the variables that make up this joint.
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
Main namespace for MoveIt!
std::vector< VariableBounds > Bounds
The datatype for the joint bounds.
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
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