40 #include <boost/math/constants/constants.hpp> 
   51 constexpr 
size_t STATE_SPACE_DIMENSION = 7;
 
   58   local_variable_names_.push_back(
"trans_x");
 
   59   local_variable_names_.push_back(
"trans_y");
 
   60   local_variable_names_.push_back(
"trans_z");
 
   61   local_variable_names_.push_back(
"rot_x");
 
   62   local_variable_names_.push_back(
"rot_y");
 
   63   local_variable_names_.push_back(
"rot_z");
 
   64   local_variable_names_.push_back(
"rot_w");
 
   65   for (
size_t i = 0; i < STATE_SPACE_DIMENSION; ++i)
 
   67     variable_names_.push_back(name_ + 
"/" + local_variable_names_[i]);
 
   68     variable_index_map_[variable_names_.back()] = i;
 
   71   variable_bounds_.resize(7);
 
   73   variable_bounds_[0].position_bounded_ = 
true;
 
   74   variable_bounds_[1].position_bounded_ = 
true;
 
   75   variable_bounds_[2].position_bounded_ = 
true;
 
   76   variable_bounds_[3].position_bounded_ = 
true;
 
   77   variable_bounds_[4].position_bounded_ = 
true;
 
   78   variable_bounds_[5].position_bounded_ = 
true;
 
   79   variable_bounds_[6].position_bounded_ = 
true;
 
   81   variable_bounds_[0].min_position_ = -std::numeric_limits<double>::infinity();
 
   82   variable_bounds_[0].max_position_ = std::numeric_limits<double>::infinity();
 
   83   variable_bounds_[1].min_position_ = -std::numeric_limits<double>::infinity();
 
   84   variable_bounds_[1].max_position_ = std::numeric_limits<double>::infinity();
 
   85   variable_bounds_[2].min_position_ = -std::numeric_limits<double>::infinity();
 
   86   variable_bounds_[2].max_position_ = std::numeric_limits<double>::infinity();
 
   87   variable_bounds_[3].min_position_ = -1.0;
 
   88   variable_bounds_[3].max_position_ = 1.0;
 
   89   variable_bounds_[4].min_position_ = -1.0;
 
   90   variable_bounds_[4].max_position_ = 1.0;
 
   91   variable_bounds_[5].min_position_ = -1.0;
 
   92   variable_bounds_[5].max_position_ = 1.0;
 
   93   variable_bounds_[6].min_position_ = -1.0;
 
   94   variable_bounds_[6].max_position_ = 1.0;
 
   96   computeVariableBoundsMsg();
 
   99 double FloatingJointModel::getMaximumExtent(
const Bounds& other_bounds)
 const 
  101   double dx = other_bounds[0].max_position_ - other_bounds[0].min_position_;
 
  102   double dy = other_bounds[1].max_position_ - other_bounds[1].min_position_;
 
  103   double dz = other_bounds[2].max_position_ - other_bounds[2].min_position_;
 
  104   return sqrt(dx * dx + dy * dy + dz * dz) + boost::math::constants::pi<double>() * 0.5 * angular_distance_weight_;
 
  109   return distanceTranslation(values1, values2) + angular_distance_weight_ * distanceRotation(values1, values2);
 
  112 double FloatingJointModel::distanceTranslation(
const double* values1, 
const double* values2)
 const 
  114   double dx = values1[0] - values2[0];
 
  115   double dy = values1[1] - values2[1];
 
  116   double dz = values1[2] - values2[2];
 
  117   return sqrt(dx * dx + dy * dy + dz * dz);
 
  120 double FloatingJointModel::distanceRotation(
const double* values1, 
const double* values2)
 const 
  123       fabs(values1[3] * values2[3] + values1[4] * values2[4] + values1[5] * values2[5] + values1[6] * values2[6]);
 
  124   if (dq + std::numeric_limits<double>::epsilon() >= 1.0)
 
  130 void FloatingJointModel::interpolate(
const double* from, 
const double* to, 
const double t, 
double* state)
 const 
  133   state[0] = from[0] + (to[0] - from[0]) * t;
 
  134   state[1] = from[1] + (to[1] - from[1]) * t;
 
  135   state[2] = from[2] + (to[2] - from[2]) * t;
 
  137   double dq = fabs(from[3] * to[3] + from[4] * to[4] + from[5] * to[5] + from[6] * to[6]);
 
  138   double theta = (dq + std::numeric_limits<double>::epsilon() >= 1.0) ? 0.0 : acos(dq);
 
  139   if (theta > std::numeric_limits<double>::epsilon())
 
  141     double d = 1.0 / sin(theta);
 
  142     double s0 = sin((1.0 - t) * theta);
 
  143     double s1 = sin(t * theta);
 
  146     state[3] = (from[3] * s0 + to[3] * s1) * 
d;
 
  147     state[4] = (from[4] * s0 + to[4] * s1) * 
d;
 
  148     state[5] = (from[5] * s0 + to[5] * s1) * 
d;
 
  149     state[6] = (from[6] * s0 + to[6] * s1) * 
d;
 
  160 bool FloatingJointModel::satisfiesPositionBounds(
const double* values, 
const Bounds& bounds, 
double margin)
 const 
  162   if (values[0] < bounds[0].min_position_ - margin || values[0] > bounds[0].max_position_ + margin)
 
  164   if (values[1] < bounds[1].min_position_ - margin || values[1] > bounds[1].max_position_ + margin)
 
  166   if (values[2] < bounds[2].min_position_ - margin || values[2] > bounds[2].max_position_ + margin)
 
  169   return fabs(norm_sqr - 1.0) <= std::numeric_limits<float>::epsilon() * 10.0;
 
  172 bool FloatingJointModel::normalizeRotation(
double* values)
 const 
  176   if (fabs(norm_sqr - 1.0) > std::numeric_limits<double>::epsilon() * 100.0)
 
  178     double norm = sqrt(norm_sqr);
 
  179     if (norm < std::numeric_limits<double>::epsilon() * 100.0)
 
  181       ROS_WARN_NAMED(
"robot_model", 
"Quaternion is zero in RobotState representation. Setting to identity");
 
  200 unsigned int FloatingJointModel::getStateSpaceDimension()
 const 
  202   return STATE_SPACE_DIMENSION;
 
  205 bool FloatingJointModel::enforcePositionBounds(
double* values, 
const Bounds& bounds)
 const 
  207   bool result = normalizeRotation(values);
 
  208   for (
unsigned int i = 0; i < 3; ++i)
 
  210     if (values[i] < bounds[i].min_position_)
 
  212       values[i] = bounds[i].min_position_;
 
  215     else if (values[i] > bounds[i].max_position_)
 
  217       values[i] = bounds[i].max_position_;
 
  224 void FloatingJointModel::computeTransform(
const double* joint_values, Eigen::Isometry3d& transf)
 const 
  226   transf = Eigen::Isometry3d(
 
  227       Eigen::Translation3d(joint_values[0], joint_values[1], joint_values[2]) *
 
  228       Eigen::Quaterniond(joint_values[6], joint_values[3], joint_values[4], joint_values[5]).normalized());
 
  231 void FloatingJointModel::computeVariablePositions(
const Eigen::Isometry3d& transf, 
double* joint_values)
 const 
  233   joint_values[0] = transf.translation().x();
 
  234   joint_values[1] = transf.translation().y();
 
  235   joint_values[2] = transf.translation().z();
 
  237   Eigen::Quaterniond q(transf.linear());
 
  238   joint_values[3] = q.x();
 
  239   joint_values[4] = q.y();
 
  240   joint_values[5] = q.z();
 
  241   joint_values[6] = q.w();
 
  244 void FloatingJointModel::getVariableDefaultPositions(
double* values, 
const Bounds& bounds)
 const 
  246   for (
unsigned int i = 0; i < 3; ++i)
 
  249     if (bounds[i].min_position_ <= 0.0 && bounds[i].max_position_ >= 0.0)
 
  252       values[i] = (bounds[i].min_position_ + bounds[i].max_position_) / 2.0;
 
  262                                                     const Bounds& bounds)
 const 
  264   if (bounds[0].max_position_ >= std::numeric_limits<double>::infinity() ||
 
  265       bounds[0].min_position_ <= -std::numeric_limits<double>::infinity())
 
  269   if (bounds[1].max_position_ >= std::numeric_limits<double>::infinity() ||
 
  270       bounds[1].min_position_ <= -std::numeric_limits<double>::infinity())
 
  274   if (bounds[2].max_position_ >= std::numeric_limits<double>::infinity() ||
 
  275       bounds[2].min_position_ <= -std::numeric_limits<double>::infinity())
 
  289                                                           const Bounds& bounds, 
const double* seed,
 
  292   if (bounds[0].max_position_ >= std::numeric_limits<double>::infinity() ||
 
  293       bounds[0].min_position_ <= -std::numeric_limits<double>::infinity())
 
  297                                 std::min(bounds[0].max_position_, seed[0] + 
distance));
 
  298   if (bounds[1].max_position_ >= std::numeric_limits<double>::infinity() ||
 
  299       bounds[1].min_position_ <= -std::numeric_limits<double>::infinity())
 
  303                                 std::min(bounds[1].max_position_, seed[1] + 
distance));
 
  304   if (bounds[2].max_position_ >= std::numeric_limits<double>::infinity() ||
 
  305       bounds[2].min_position_ <= -std::numeric_limits<double>::infinity())
 
  309                                 std::min(bounds[2].max_position_, seed[2] + 
distance));
 
  311   double da = angular_distance_weight_ * 
distance;
 
  312   if (da >= .25 * boost::math::constants::pi<double>())
 
  331     double norm = sqrt(ax * ax + ay * ay + az * az);
 
  334       q[0] = q[1] = q[2] = 0.0;
 
  339       double s = sin(angle / 2.0);
 
  340       q[0] = 
s * ax / norm;
 
  341       q[1] = 
s * ay / norm;
 
  342       q[2] = 
s * az / norm;
 
  343       q[3] = cos(angle / 2.0);
 
  346     values[3] = seed[6] * q[0] + seed[3] * q[3] + seed[4] * q[2] - seed[5] * q[1];
 
  347     values[4] = seed[6] * q[1] + seed[4] * q[3] + seed[5] * q[0] - seed[3] * q[2];
 
  348     values[5] = seed[6] * q[2] + seed[5] * q[3] + seed[3] * q[1] - seed[4] * q[0];
 
  349     values[6] = seed[6] * q[3] - seed[3] * q[0] - seed[4] * q[1] - seed[5] * q[2];