50   , parent_link_model_(nullptr)
 
   51   , child_link_model_(nullptr)
 
   56   , distance_factor_(1.0)
 
   57   , first_variable_index_(-1)
 
   62 JointModel::~JointModel() = 
default;
 
   64 std::string JointModel::getTypeName()
 const 
   85 int JointModel::getLocalVariableIndex(
const std::string& variable)
 const 
   87   VariableIndexMap::const_iterator it = variable_index_map_.find(variable);
 
   88   if (it == variable_index_map_.end())
 
   89     throw Exception(
"Could not find variable '" + variable + 
"' to get bounds for within joint '" + name_ + 
"'");
 
   93 bool JointModel::harmonizePosition(
double* , 
const Bounds& )
 const 
   98 bool JointModel::enforceVelocityBounds(
double* values, 
const Bounds& other_bounds)
 const 
  101   for (std::size_t i = 0; i < other_bounds.size(); ++i)
 
  102     if (other_bounds[i].max_velocity_ < values[i])
 
  104       values[i] = other_bounds[i].max_velocity_;
 
  107     else if (other_bounds[i].min_velocity_ > values[i])
 
  109       values[i] = other_bounds[i].min_velocity_;
 
  115 bool JointModel::satisfiesVelocityBounds(
const double* values, 
const Bounds& other_bounds, 
double margin)
 const 
  117   for (std::size_t i = 0; i < other_bounds.size(); ++i)
 
  119     if (!other_bounds[i].velocity_bounded_)
 
  123     if (other_bounds[i].max_velocity_ + margin < 
values[i])
 
  125     else if (other_bounds[i].min_velocity_ - margin > 
values[i])
 
  131 bool JointModel::satisfiesAccelerationBounds(
const double* values, 
const Bounds& other_bounds, 
double margin)
 const 
  133   for (std::size_t i = 0; i < other_bounds.size(); ++i)
 
  135     if (!other_bounds[i].acceleration_bounded_)
 
  139     if (other_bounds[i].max_acceleration_ + margin < 
values[i])
 
  141     else if (other_bounds[i].min_acceleration_ - margin > 
values[i])
 
  147 const VariableBounds& JointModel::getVariableBounds(
const std::string& variable)
 const 
  149   return variable_bounds_[getLocalVariableIndex(variable)];
 
  152 void JointModel::setVariableBounds(
const std::string& variable, 
const VariableBounds& bounds)
 
  154   variable_bounds_[getLocalVariableIndex(variable)] = bounds;
 
  155   computeVariableBoundsMsg();
 
  158 void JointModel::setVariableBounds(
const std::vector<moveit_msgs::JointLimits>& jlim)
 
  160   for (std::size_t j = 0; j < variable_names_.size(); ++j)
 
  161     for (
const moveit_msgs::JointLimits& joint_limit : jlim)
 
  162       if (joint_limit.joint_name == variable_names_[j])
 
  164         variable_bounds_[j].position_bounded_ = joint_limit.has_position_limits;
 
  165         if (joint_limit.has_position_limits)
 
  167           variable_bounds_[j].min_position_ = joint_limit.min_position;
 
  168           variable_bounds_[j].max_position_ = joint_limit.max_position;
 
  170         variable_bounds_[j].velocity_bounded_ = joint_limit.has_velocity_limits;
 
  171         if (joint_limit.has_velocity_limits)
 
  173           variable_bounds_[j].min_velocity_ = -joint_limit.max_velocity;
 
  174           variable_bounds_[j].max_velocity_ = joint_limit.max_velocity;
 
  176         variable_bounds_[j].acceleration_bounded_ = joint_limit.has_acceleration_limits;
 
  177         if (joint_limit.has_acceleration_limits)
 
  179           variable_bounds_[j].min_acceleration_ = -joint_limit.max_acceleration;
 
  180           variable_bounds_[j].max_acceleration_ = joint_limit.max_acceleration;
 
  184   computeVariableBoundsMsg();
 
  187 void JointModel::computeVariableBoundsMsg()
 
  189   variable_bounds_msg_.clear();
 
  190   for (std::size_t i = 0; i < variable_bounds_.size(); ++i)
 
  192     moveit_msgs::JointLimits lim;
 
  193     lim.joint_name = variable_names_[i];
 
  194     lim.has_position_limits = variable_bounds_[i].position_bounded_;
 
  195     lim.min_position = variable_bounds_[i].min_position_;
 
  196     lim.max_position = variable_bounds_[i].max_position_;
 
  197     lim.has_velocity_limits = variable_bounds_[i].velocity_bounded_;
 
  198     lim.max_velocity = std::min(fabs(variable_bounds_[i].min_velocity_), fabs(variable_bounds_[i].max_velocity_));
 
  199     lim.has_acceleration_limits = variable_bounds_[i].acceleration_bounded_;
 
  200     lim.max_acceleration =
 
  201         std::min(fabs(variable_bounds_[i].min_acceleration_), fabs(variable_bounds_[i].max_acceleration_));
 
  202     variable_bounds_msg_.push_back(lim);
 
  206 void JointModel::setMimic(
const JointModel* mimic, 
double factor, 
double offset)
 
  209   mimic_factor_ = factor;
 
  210   mimic_offset_ = offset;
 
  215   mimic_requests_.push_back(joint);
 
  218 void JointModel::addDescendantJointModel(
const JointModel* joint)
 
  220   descendant_joint_models_.push_back(joint);
 
  222     non_fixed_descendant_joint_models_.push_back(joint);
 
  225 void JointModel::addDescendantLinkModel(
const LinkModel* link)
 
  227   descendant_link_models_.push_back(link);
 
  232 inline void printBoundHelper(std::ostream& out, 
double v)
 
  234   if (v <= -std::numeric_limits<double>::infinity())
 
  236   else if (v >= std::numeric_limits<double>::infinity())
 
  243 std::ostream& 
operator<<(std::ostream& out, 
const VariableBounds& b)
 
  245   out << 
"P." << (b.position_bounded_ ? 
"bounded" : 
"unbounded") << 
" [";
 
  246   printBoundHelper(out, b.min_position_);
 
  248   printBoundHelper(out, b.max_position_);
 
  250       << 
"V." << (b.velocity_bounded_ ? 
"bounded" : 
"unbounded") << 
" [";
 
  251   printBoundHelper(out, b.min_velocity_);
 
  253   printBoundHelper(out, b.max_velocity_);
 
  255       << 
"A." << (b.acceleration_bounded_ ? 
"bounded" : 
"unbounded") << 
" [";
 
  256   printBoundHelper(out, b.min_acceleration_);
 
  258   printBoundHelper(out, b.max_acceleration_);