39#include <Eigen/Geometry>
40#include <geometric_shapes/check_isometry.h>
43#include <rclcpp/logger.hpp>
44#include <rclcpp/logging.hpp>
53constexpr size_t STATE_SPACE_DIMENSION = 7;
63 :
JointModel(name, joint_index, first_variable_index), angular_distance_weight_(1.0)
73 for (
size_t i = 0; i < STATE_SPACE_DIMENSION; ++i)
89 variable_bounds_[0].min_position_ = -std::numeric_limits<double>::infinity();
91 variable_bounds_[1].min_position_ = -std::numeric_limits<double>::infinity();
93 variable_bounds_[2].min_position_ = -std::numeric_limits<double>::infinity();
109 double dx = other_bounds[0].max_position_ - other_bounds[0].min_position_;
110 double dy = other_bounds[1].max_position_ - other_bounds[1].min_position_;
111 double dz = other_bounds[2].max_position_ - other_bounds[2].min_position_;
112 return sqrt(dx * dx + dy * dy + dz * dz) + M_PI * 0.5 * angular_distance_weight_;
122 double dx = values1[0] - values2[0];
123 double dy = values1[1] - values2[1];
124 double dz = values1[2] - values2[2];
125 return sqrt(dx * dx + dy * dy + dz * dz);
131 const auto q1 = Eigen::Quaterniond(values1[6], values1[3], values1[4], values1[5]).normalized();
132 const auto q2 = Eigen::Quaterniond(values2[6], values2[3], values2[4], values2[5]).normalized();
133 return q2.angularDistance(q1);
139 state[0] = from[0] + (to[0] - from[0]) * t;
140 state[1] = from[1] + (to[1] - from[1]) * t;
141 state[2] = from[2] + (to[2] - from[2]) * t;
144 if (abs(from[3] - to[3]) + abs(from[4] - to[4]) + abs(from[5] - to[5]) + abs(from[6] - to[6]) >
145 std::numeric_limits<double>::epsilon())
148 Eigen::Quaterniond q1(from[6], from[3], from[4], from[5]);
149 Eigen::Quaterniond q2(to[6], to[3], to[4], to[5]);
151 Eigen::Quaterniond q = q1.slerp(t, q2);
169 if (values[0] < bounds[0].min_position_ - margin || values[0] > bounds[0].max_position_ + margin)
171 if (values[1] < bounds[1].min_position_ - margin || values[1] > bounds[1].max_position_ + margin)
173 if (values[2] < bounds[2].min_position_ - margin || values[2] > bounds[2].max_position_ + margin)
175 double norm_sqr = values[3] * values[3] + values[4] * values[4] + values[5] * values[5] + values[6] * values[6];
176 return fabs(norm_sqr - 1.0) <= std::numeric_limits<double>::epsilon() * 10.0;
182 double norm_sqr = values[3] * values[3] + values[4] * values[4] + values[5] * values[5] + values[6] * values[6];
183 if (fabs(norm_sqr - 1.0) > std::numeric_limits<double>::epsilon() * 100.0)
185 double norm = sqrt(norm_sqr);
186 if (norm < std::numeric_limits<double>::epsilon() * 100.0)
188 RCLCPP_WARN(getLogger(),
"Quaternion is zero in RobotState representation. Setting to identity");
209 return STATE_SPACE_DIMENSION;
215 for (
unsigned int i = 0; i < 3; ++i)
217 if (values[i] < bounds[i].min_position_)
219 values[i] = bounds[i].min_position_;
222 else if (values[i] > bounds[i].max_position_)
224 values[i] = bounds[i].max_position_;
233 transf = Eigen::Isometry3d(
234 Eigen::Translation3d(joint_values[0], joint_values[1], joint_values[2]) *
235 Eigen::Quaterniond(joint_values[6], joint_values[3], joint_values[4], joint_values[5]).normalized());
240 joint_values[0] = transf.translation().x();
241 joint_values[1] = transf.translation().y();
242 joint_values[2] = transf.translation().z();
243 ASSERT_ISOMETRY(transf)
244 Eigen::Quaterniond q(transf.linear());
245 joint_values[3] = q.x();
246 joint_values[4] = q.y();
247 joint_values[5] = q.z();
248 joint_values[6] = q.w();
253 for (
unsigned int i = 0; i < 3; ++i)
256 if (bounds[i].min_position_ <= 0.0 && bounds[i].max_position_ >= 0.0)
262 values[i] = (bounds[i].min_position_ + bounds[i].max_position_) / 2.0;
273 const Bounds& bounds)
const
275 if (bounds[0].max_position_ >= std::numeric_limits<double>::infinity() ||
276 bounds[0].min_position_ <= -std::numeric_limits<double>::infinity())
282 values[0] = rng.uniformReal(bounds[0].min_position_, bounds[0].max_position_);
284 if (bounds[1].max_position_ >= std::numeric_limits<double>::infinity() ||
285 bounds[1].min_position_ <= -std::numeric_limits<double>::infinity())
291 values[1] = rng.uniformReal(bounds[1].min_position_, bounds[1].max_position_);
293 if (bounds[2].max_position_ >= std::numeric_limits<double>::infinity() ||
294 bounds[2].min_position_ <= -std::numeric_limits<double>::infinity())
300 values[2] = rng.uniformReal(bounds[2].min_position_, bounds[2].max_position_);
312 const Bounds& bounds,
const double* near,
313 const double distance)
const
315 if (bounds[0].max_position_ >= std::numeric_limits<double>::infinity() ||
316 bounds[0].min_position_ <= -std::numeric_limits<double>::infinity())
322 values[0] = rng.uniformReal(std::max(bounds[0].min_position_, near[0] -
distance),
323 std::min(bounds[0].max_position_, near[0] +
distance));
325 if (bounds[1].max_position_ >= std::numeric_limits<double>::infinity() ||
326 bounds[1].min_position_ <= -std::numeric_limits<double>::infinity())
332 values[1] = rng.uniformReal(std::max(bounds[1].min_position_, near[1] -
distance),
333 std::min(bounds[1].max_position_, near[1] +
distance));
335 if (bounds[2].max_position_ >= std::numeric_limits<double>::infinity() ||
336 bounds[2].min_position_ <= -std::numeric_limits<double>::infinity())
342 values[2] = rng.uniformReal(std::max(bounds[2].min_position_, near[2] -
distance),
343 std::min(bounds[2].max_position_, near[2] +
distance));
346 double da = angular_distance_weight_ *
distance;
347 if (da >= .25 * M_PI)
360 double ax = rng.gaussian01();
361 double ay = rng.gaussian01();
362 double az = rng.gaussian01();
363 double angle = 2.0 * pow(rng.uniform01(), 1.0 / 3.0) * da;
366 double norm = sqrt(ax * ax + ay * ay + az * az);
369 q[0] = q[1] = q[2] = 0.0;
374 double s = sin(angle / 2.0);
375 q[0] = s * ax / norm;
376 q[1] = s * ay / norm;
377 q[2] = s * az / norm;
378 q[3] = cos(angle / 2.0);
381 values[3] = near[6] * q[0] + near[3] * q[3] + near[4] * q[2] - near[5] * q[1];
382 values[4] = near[6] * q[1] + near[4] * q[3] + near[5] * q[0] - near[3] * q[2];
383 values[5] = near[6] * q[2] + near[5] * q[3] + near[3] * q[1] - near[4] * q[0];
384 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.
rclcpp::Logger getLogger()
Main namespace for MoveIt.
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.