39 #include <Eigen/Geometry>
40 #include <geometric_shapes/check_isometry.h>
43 #include <rclcpp/logger.hpp>
44 #include <rclcpp/logging.hpp>
50 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"moveit_robot_model.floating_joint_model");
53 constexpr
size_t STATE_SPACE_DIMENSION = 7;
58 :
JointModel(
name, joint_index, first_variable_index), angular_distance_weight_(1.0)
68 for (
size_t i = 0; i < STATE_SPACE_DIMENSION; ++i)
84 variable_bounds_[0].min_position_ = -std::numeric_limits<double>::infinity();
86 variable_bounds_[1].min_position_ = -std::numeric_limits<double>::infinity();
88 variable_bounds_[2].min_position_ = -std::numeric_limits<double>::infinity();
104 double dx = other_bounds[0].max_position_ - other_bounds[0].min_position_;
105 double dy = other_bounds[1].max_position_ - other_bounds[1].min_position_;
106 double dz = other_bounds[2].max_position_ - other_bounds[2].min_position_;
107 return sqrt(dx * dx + dy * dy + dz * dz) + M_PI * 0.5 * angular_distance_weight_;
117 double dx = values1[0] - values2[0];
118 double dy = values1[1] - values2[1];
119 double dz = values1[2] - values2[2];
120 return sqrt(dx * dx + dy * dy + dz * dz);
126 const auto q1 = Eigen::Quaterniond(values1[6], values1[3], values1[4], values1[5]).normalized();
127 const auto q2 = Eigen::Quaterniond(values2[6], values2[3], values2[4], values2[5]).normalized();
128 return q2.angularDistance(q1);
134 state[0] = from[0] + (to[0] - from[0]) * t;
135 state[1] = from[1] + (to[1] - from[1]) * t;
136 state[2] = from[2] + (to[2] - from[2]) * t;
139 if (abs(from[3] - to[3]) + abs(from[4] - to[4]) + abs(from[5] - to[5]) + abs(from[6] - to[6]) >
140 std::numeric_limits<double>::epsilon())
143 Eigen::Quaterniond q1(from[6], from[3], from[4], from[5]);
144 Eigen::Quaterniond q2(to[6], to[3], to[4], to[5]);
146 Eigen::Quaterniond q = q1.slerp(t, q2);
164 if (values[0] < bounds[0].min_position_ - margin || values[0] > bounds[0].max_position_ + margin)
166 if (values[1] < bounds[1].min_position_ - margin || values[1] > bounds[1].max_position_ + margin)
168 if (values[2] < bounds[2].min_position_ - margin || values[2] > bounds[2].max_position_ + margin)
170 double norm_sqr = values[3] * values[3] + values[4] * values[4] + values[5] * values[5] + values[6] * values[6];
171 return fabs(norm_sqr - 1.0) <= std::numeric_limits<float>::epsilon() * 10.0;
177 double norm_sqr = values[3] * values[3] + values[4] * values[4] + values[5] * values[5] + values[6] * values[6];
178 if (fabs(norm_sqr - 1.0) > std::numeric_limits<double>::epsilon() * 100.0)
180 double norm = sqrt(norm_sqr);
181 if (norm < std::numeric_limits<double>::epsilon() * 100.0)
183 RCLCPP_WARN(LOGGER,
"Quaternion is zero in RobotState representation. Setting to identity");
204 return STATE_SPACE_DIMENSION;
210 for (
unsigned int i = 0; i < 3; ++i)
212 if (values[i] < bounds[i].min_position_)
214 values[i] = bounds[i].min_position_;
217 else if (values[i] > bounds[i].max_position_)
219 values[i] = bounds[i].max_position_;
228 transf = Eigen::Isometry3d(
229 Eigen::Translation3d(joint_values[0], joint_values[1], joint_values[2]) *
230 Eigen::Quaterniond(joint_values[6], joint_values[3], joint_values[4], joint_values[5]).normalized());
235 joint_values[0] = transf.translation().x();
236 joint_values[1] = transf.translation().y();
237 joint_values[2] = transf.translation().z();
238 ASSERT_ISOMETRY(transf)
239 Eigen::Quaterniond q(transf.linear());
240 joint_values[3] = q.x();
241 joint_values[4] = q.y();
242 joint_values[5] = q.z();
243 joint_values[6] = q.w();
248 for (
unsigned int i = 0; i < 3; ++i)
251 if (bounds[i].min_position_ <= 0.0 && bounds[i].max_position_ >= 0.0)
254 values[i] = (bounds[i].min_position_ + bounds[i].max_position_) / 2.0;
264 const Bounds& bounds)
const
266 if (bounds[0].max_position_ >= std::numeric_limits<double>::infinity() ||
267 bounds[0].min_position_ <= -std::numeric_limits<double>::infinity())
270 values[0] = rng.uniformReal(bounds[0].min_position_, bounds[0].max_position_);
271 if (bounds[1].max_position_ >= std::numeric_limits<double>::infinity() ||
272 bounds[1].min_position_ <= -std::numeric_limits<double>::infinity())
275 values[1] = rng.uniformReal(bounds[1].min_position_, bounds[1].max_position_);
276 if (bounds[2].max_position_ >= std::numeric_limits<double>::infinity() ||
277 bounds[2].min_position_ <= -std::numeric_limits<double>::infinity())
280 values[2] = rng.uniformReal(bounds[2].min_position_, bounds[2].max_position_);
291 const Bounds& bounds,
const double* near,
294 if (bounds[0].max_position_ >= std::numeric_limits<double>::infinity() ||
295 bounds[0].min_position_ <= -std::numeric_limits<double>::infinity())
298 values[0] = rng.uniformReal(std::max(bounds[0].min_position_, near[0] -
distance),
299 std::min(bounds[0].max_position_, near[0] +
distance));
300 if (bounds[1].max_position_ >= std::numeric_limits<double>::infinity() ||
301 bounds[1].min_position_ <= -std::numeric_limits<double>::infinity())
304 values[1] = rng.uniformReal(std::max(bounds[1].min_position_, near[1] -
distance),
305 std::min(bounds[1].max_position_, near[1] +
distance));
306 if (bounds[2].max_position_ >= std::numeric_limits<double>::infinity() ||
307 bounds[2].min_position_ <= -std::numeric_limits<double>::infinity())
310 values[2] = rng.uniformReal(std::max(bounds[2].min_position_, near[2] -
distance),
311 std::min(bounds[2].max_position_, near[2] +
distance));
313 double da = angular_distance_weight_ *
distance;
314 if (da >= .25 * M_PI)
327 double ax = rng.gaussian01();
328 double ay = rng.gaussian01();
329 double az = rng.gaussian01();
330 double angle = 2.0 * pow(rng.uniform01(), 1.0 / 3.0) * da;
333 double norm = sqrt(ax * ax + ay * ay + az * az);
336 q[0] = q[1] = q[2] = 0.0;
341 double s = sin(angle / 2.0);
342 q[0] = s * ax / norm;
343 q[1] = s * ay / norm;
344 q[2] = s * az / norm;
345 q[3] = cos(angle / 2.0);
348 values[3] = near[6] * q[0] + near[3] * q[3] + near[4] * q[2] - near[5] * q[1];
349 values[4] = near[6] * q[1] + near[4] * q[3] + near[5] * q[0] - near[3] * q[2];
350 values[5] = near[6] * q[2] + near[5] * q[3] + near[3] * q[1] - near[4] * q[0];
351 values[6] = near[6] * q[3] - near[3] * q[0] - near[4] * q[1] - near[5] * q[2];
double distanceRotation(const double *values1, const double *values2) const
Get the distance between the rotation components of two states.
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 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....
bool normalizeRotation(double *values) const
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 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 ...
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 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 ...
double distanceTranslation(const double *values1, const double *values2) const
Get the distance between the translation components of two states.
FloatingJointModel(const std::string &name, size_t joint_index, size_t first_variable_index)
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.
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()
std::vector< std::string > local_variable_names_
The local names to use for the variables that make up this joint.
double getMaximumExtent() const
std::vector< std::string > variable_names_
The full names to use for the variables that make up this joint.
Main namespace for MoveIt.
double distance(const urdf::Pose &transform)