40 #include <boost/math/constants/constants.hpp> 
   49   : JointModel(
name), axis_(0.0, 0.0, 0.0), continuous_(false), x2_(0.0), y2_(0.0), z2_(0.0), xy_(0.0), xz_(0.0), yz_(0.0)
 
   52   variable_names_.push_back(name_);
 
   53   variable_bounds_.resize(1);
 
   54   variable_bounds_[0].position_bounded_ = 
true;
 
   55   variable_bounds_[0].min_position_ = -boost::math::constants::pi<double>();
 
   56   variable_bounds_[0].max_position_ = boost::math::constants::pi<double>();
 
   57   variable_index_map_[name_] = 0;
 
   58   computeVariableBoundsMsg();
 
   61 unsigned int RevoluteJointModel::getStateSpaceDimension()
 const 
   68   axis_ = axis.normalized();
 
   69   x2_ = axis_.x() * axis_.x();
 
   70   y2_ = axis_.y() * axis_.y();
 
   71   z2_ = axis_.z() * axis_.z();
 
   72   xy_ = axis_.x() * axis_.y();
 
   73   xz_ = axis_.x() * axis_.z();
 
   74   yz_ = axis_.y() * axis_.z();
 
   77 void RevoluteJointModel::setContinuous(
bool flag)
 
   82     variable_bounds_[0].position_bounded_ = 
false;
 
   83     variable_bounds_[0].min_position_ = -boost::math::constants::pi<double>();
 
   84     variable_bounds_[0].max_position_ = boost::math::constants::pi<double>();
 
   87     variable_bounds_[0].position_bounded_ = 
true;
 
   88   computeVariableBoundsMsg();
 
   91 double RevoluteJointModel::getMaximumExtent(
const Bounds& )
 const 
   93   return variable_bounds_[0].max_position_ - variable_bounds_[0].min_position_;
 
   96 void RevoluteJointModel::getVariableDefaultPositions(
double* values, 
const Bounds& bounds)
 const 
   99   if (bounds[0].min_position_ <= 0.0 && bounds[0].max_position_ >= 0.0)
 
  102     values[0] = (bounds[0].min_position_ + bounds[0].max_position_) / 2.0;
 
  106                                                     const Bounds& bounds)
 const 
  112                                                           const Bounds& bounds, 
const double* seed,
 
  118     enforcePositionBounds(
values, bounds);
 
  122                                 std::min(bounds[0].max_position_, seed[0] + 
distance));
 
  125 void RevoluteJointModel::interpolate(
const double* from, 
const double* to, 
const double t, 
double* state)
 const 
  129     double diff = to[0] - from[0];
 
  130     if (fabs(diff) <= boost::math::constants::pi<double>())
 
  131       state[0] = from[0] + diff * 
t;
 
  135         diff = 2.0 * boost::math::constants::pi<double>() - diff;
 
  137         diff = -2.0 * boost::math::constants::pi<double>() - diff;
 
  138       state[0] = from[0] - diff * 
t;
 
  140       if (state[0] > boost::math::constants::pi<double>())
 
  141         state[0] -= 2.0 * boost::math::constants::pi<double>();
 
  142       else if (state[0] < -boost::math::constants::pi<double>())
 
  143         state[0] += 2.0 * boost::math::constants::pi<double>();
 
  147     state[0] = from[0] + (to[0] - from[0]) * t;
 
  154     double d = fmod(fabs(values1[0] - values2[0]), 2.0 * boost::math::constants::pi<double>());
 
  155     return (
d > boost::math::constants::pi<double>()) ? 2.0 * boost::math::constants::pi<double>() - 
d : 
d;
 
  158     return fabs(values1[0] - values2[0]);
 
  161 bool RevoluteJointModel::satisfiesPositionBounds(
const double* values, 
const Bounds& bounds, 
double margin)
 const 
  166     return !(
values[0] < bounds[0].min_position_ - margin || 
values[0] > bounds[0].max_position_ + margin);
 
  169 bool RevoluteJointModel::harmonizePosition(
double* values, 
const JointModel::Bounds& other_bounds)
 const 
  171   bool modified = 
false;
 
  172   if (*values < other_bounds[0].min_position_)
 
  174     while (*
values + 2 * 
M_PI <= other_bounds[0].max_position_)
 
  180   else if (*values > other_bounds[0].max_position_)
 
  182     while (*
values - 2 * 
M_PI >= other_bounds[0].min_position_)
 
  191 bool RevoluteJointModel::enforcePositionBounds(
double* values, 
const Bounds& bounds)
 const 
  196     if (v <= -boost::math::constants::pi<double>() || v > boost::math::constants::pi<double>())
 
  198       v = fmod(v, 2.0 * boost::math::constants::pi<double>());
 
  199       if (v <= -boost::math::constants::pi<double>())
 
  200         v += 2.0 * boost::math::constants::pi<double>();
 
  201       else if (v > boost::math::constants::pi<double>())
 
  202         v -= 2.0 * boost::math::constants::pi<double>();
 
  208     if (
values[0] < bounds[0].min_position_)
 
  210       values[0] = bounds[0].min_position_;
 
  213     else if (
values[0] > bounds[0].max_position_)
 
  215       values[0] = bounds[0].max_position_;
 
  222 void RevoluteJointModel::computeTransform(
const double* joint_values, Eigen::Isometry3d& transf)
 const 
  224   const double c = cos(joint_values[0]);
 
  225   const double s = sin(joint_values[0]);
 
  226   const double t = 1.0 - c;
 
  227   const double txy = 
t * xy_;
 
  228   const double txz = 
t * xz_;
 
  229   const double tyz = 
t * yz_;
 
  231   const double zs = axis_.z() * 
s;
 
  232   const double ys = axis_.y() * 
s;
 
  233   const double xs = axis_.x() * 
s;
 
  236   double* 
d = transf.data();
 
  261 void RevoluteJointModel::computeVariablePositions(
const Eigen::Isometry3d& transf, 
double* joint_values)
 const 
  264   Eigen::Quaterniond q(transf.linear());
 
  267   axis_.array().abs().maxCoeff(&max_idx);
 
  268   joint_values[0] = 2. * atan2(q.vec()[max_idx] / axis_[max_idx], q.w());