56 constexpr 
char LOGNAME[] = 
"robot_state";
 
   61   , has_velocity_(false)
 
   62   , has_acceleration_(false)
 
   64   , dirty_link_transforms_(nullptr)
 
   65   , dirty_collision_body_transforms_(nullptr)
 
   70     throw std::invalid_argument(
"RobotState cannot be constructed with nullptr RobotModelConstPtr");
 
   73   dirty_link_transforms_ = robot_model_->getRootJoint();
 
   80   robot_model_ = other.robot_model_;
 
   95   static_assert((
sizeof(Eigen::Isometry3d) / EIGEN_MAX_ALIGN_BYTES) * EIGEN_MAX_ALIGN_BYTES == 
sizeof(Eigen::Isometry3d),
 
   96                 "sizeof(Eigen::Isometry3d) should be a multiple of EIGEN_MAX_ALIGN_BYTES");
 
   98   constexpr 
unsigned int extra_alignment_bytes = EIGEN_MAX_ALIGN_BYTES - 1;
 
  100   const int nr_doubles_for_dirty_joint_transforms =
 
  101       1 + 
robot_model_->getJointModelCount() / (
sizeof(double) / 
sizeof(
unsigned char));
 
  105       sizeof(
double) * (
robot_model_->getVariableCount() * 3 + nr_doubles_for_dirty_joint_transforms) +
 
  106       extra_alignment_bytes;
 
  126   const int nr_doubles_for_dirty_joint_transforms =
 
  127       1 + 
robot_model_->getJointModelCount() / (
sizeof(double) / 
sizeof(
unsigned char));
 
  170     const int nr_doubles_for_dirty_joint_transforms =
 
  171         1 + 
robot_model_->getJointModelCount() / (
sizeof(double) / 
sizeof(
unsigned char));
 
  178              nr_doubles_for_dirty_joint_transforms);
 
  185     attachBody(std::make_unique<AttachedBody>(*attached_body.second));
 
  192     ROS_WARN_NAMED(
LOGNAME, 
"Returning dirty joint transforms for joint '%s'", joint->getName().c_str());
 
  311     joint->getVariableRandomPositions(rng, 
position_ + joint->getFirstVariableIndex());
 
  316                                             const std::vector<double>& distances)
 
  325                                             const std::vector<double>& distances,
 
  329   assert(distances.size() == joints.size());
 
  330   for (std::size_t i = 0; i < joints.size(); ++i)
 
  332     const int idx = joints[i]->getFirstVariableIndex();
 
  333     joints[i]->getVariableRandomPositionsNearBy(rng, 
position_ + joints[i]->getFirstVariableIndex(),
 
  353     const int idx = joint->getFirstVariableIndex();
 
  354     joint->getVariableRandomPositionsNearBy(rng, 
position_ + joint->getFirstVariableIndex(), seed.
position_ + idx,
 
  362   std::map<std::string, double> m;
 
  391   for (
const std::pair<const std::string, double>& it : variable_map)
 
  402                                 std::vector<std::string>& missing_variables)
 const 
  404   missing_variables.clear();
 
  406   for (
const std::string& variable_name : nm)
 
  407     if (variable_map.find(variable_name) == variable_map.end())
 
  408       if (
robot_model_->getJointOfVariable(variable_name)->getMimic() == 
nullptr)
 
  409         missing_variables.push_back(variable_name);
 
  413                                       std::vector<std::string>& missing_variables)
 
  420                                       const std::vector<double>& variable_position)
 
  422   for (std::size_t i = 0; i < variable_names.size(); ++i)
 
  435   for (
const std::pair<const std::string, double>& it : variable_map)
 
  440                                        std::vector<std::string>& missing_variables)
 
  447                                        const std::vector<double>& variable_velocity)
 
  450   assert(variable_names.size() == variable_velocity.size());
 
  451   for (std::size_t i = 0; i < variable_names.size(); ++i)
 
  458   for (
const std::pair<const std::string, double>& it : variable_map)
 
  463                                           std::vector<std::string>& missing_variables)
 
  470                                           const std::vector<double>& variable_acceleration)
 
  473   assert(variable_names.size() == variable_acceleration.size());
 
  474   for (std::size_t i = 0; i < variable_names.size(); ++i)
 
  481   for (
const std::pair<const std::string, double>& it : variable_map)
 
  486                                    std::vector<std::string>& missing_variables)
 
  493                                    const std::vector<double>& variable_effort)
 
  496   assert(variable_names.size() == variable_effort.size());
 
  497   for (std::size_t i = 0; i < variable_names.size(); ++i)
 
  519   memcpy(
effort_ + joint->getFirstVariableIndex(), effort, joint->getVariableCount() * 
sizeof(
double));
 
  529     for (std::size_t i = 0; i < il.size(); ++i)
 
  538   for (std::size_t i = 0; i < il.size(); ++i)
 
  550     i += jm->getVariableCount();
 
  557   assert(
values.size() == group->getActiveVariableCount());
 
  559   for (
const JointModel* jm : group->getActiveJointModels())
 
  562     i += jm->getVariableCount();
 
  573     for (std::size_t i = 0; i < il.size(); ++i)
 
  581   for (std::size_t i = 0; i < il.size(); ++i)
 
  593     for (std::size_t i = 0; i < il.size(); ++i)
 
  601   const std::vector<int>& il = group->getVariableIndexList();
 
  602   for (std::size_t i = 0; i < il.size(); ++i)
 
  612     for (std::size_t i = 0; i < il.size(); ++i)
 
  620   for (std::size_t i = 0; i < il.size(); ++i)
 
  632     for (std::size_t i = 0; i < il.size(); ++i)
 
  640   const std::vector<int>& il = group->getVariableIndexList();
 
  641   for (std::size_t i = 0; i < il.size(); ++i)
 
  651     for (std::size_t i = 0; i < il.size(); ++i)
 
  659   for (std::size_t i = 0; i < il.size(); ++i)
 
  689       const std::vector<int>& ot_id = link->areCollisionOriginTransformsIdentity();
 
  690       const int index_co = link->getFirstCollisionBodyTransformIndex();
 
  691       const int index_l = link->getLinkIndex();
 
  692       for (std::size_t j = 0, end = ot.size(); j != end; ++j)
 
  720   for (
const LinkModel* link : 
start->getDescendantLinkModels())
 
  722     int idx_link = link->getLinkIndex();
 
  727       if (link->parentJointIsFixed())  
 
  732         if (link->jointOriginTransformIsIdentity())  
 
  743       if (link->jointOriginTransformIsIdentity())
 
  747             link->getJointOriginTransform().affine() * 
getJointTransform(link->getParentJointModel()).matrix();
 
  753     attached_body.second->computeTransform(
 
  771   const std::vector<const JointModel*>& cj = link->getChildJointModels();
 
  782       child_link = parent_link;
 
  822     const auto& body{ it->second };
 
  823     link = body->getAttachedLink();
 
  832       const auto& body{ it.second };
 
  833       const Eigen::Isometry3d& subframe = body->getSubframeTransform(frame, &found);
 
  838         link = body->getAttachedLink();
 
  847   Eigen::Isometry3d link_transform;
 
  848   auto* parent = 
getRobotModel()->getRigidlyConnectedParentLinkModel(link, link_transform, jmg);
 
  849   if (parent && transform)
 
  857   const std::vector<const JointModel*>& jm = 
robot_model_->getActiveJointModels();
 
  858   for (
const JointModel* joint : jm)
 
  866   const std::vector<const JointModel*>& jm = group->getActiveJointModels();
 
  867   for (
const JointModel* joint : jm)
 
  875   const std::vector<const JointModel*>& jm = 
robot_model_->getActiveJointModels();
 
  889   for (
const JointModel* jm : 
robot_model_->getActiveJointModels())
 
  895   for (
const JointModel* jm : joint_group->getActiveJointModels())
 
  909 std::pair<double, const JointModel*>
 
  912   double distance = std::numeric_limits<double>::max();
 
  913   const JointModel* 
index = 
nullptr;
 
  914   for (
const JointModel* joint : joints)
 
  919       if (
static_cast<const RevoluteJointModel*
>(joint)->isContinuous())
 
  924     std::vector<double> lower_bounds(bounds.size()), upper_bounds(bounds.size());
 
  925     for (std::size_t j = 0; j < bounds.size(); ++j)
 
  927       lower_bounds[j] = bounds[j].min_position_;
 
  928       upper_bounds[j] = bounds[j].max_position_;
 
  930     double new_distance = joint->distance(joint_values, &lower_bounds[0]);
 
  936     new_distance = joint->distance(joint_values, &upper_bounds[0]);
 
  943   return std::make_pair(
distance, index);
 
  951     const int idx = joint_id->getFirstVariableIndex();
 
  952     const std::vector<VariableBounds>& bounds = joint_id->getVariableBounds();
 
  955     for (std::size_t var_id = 0; var_id < joint_id->getVariableCount(); ++var_id)
 
  959       if (dtheta > dt * bounds[var_id].max_velocity_)
 
  972     const int idx = joint->getFirstVariableIndex();
 
  987 void RobotState::interpolate(
const RobotState& to, 
double t, RobotState& state, 
const JointModelGroup* joint_group)
 const 
  990   const std::vector<const JointModel*>& jm = joint_group->getActiveJointModels();
 
  991   for (
const JointModel* joint : jm)
 
  993     const int idx = joint->getFirstVariableIndex();
 
  994     joint->interpolate(
position_ + idx, to.position_ + idx, t, state.position_ + idx);
 
  996   state.updateMimicJoints(joint_group);
 
 1018     return it->second.get();
 
 1034   attachBody(std::unique_ptr<AttachedBody>(attached_body));
 
 1038                             const std::vector<shapes::ShapeConstPtr>& 
shapes,
 
 1040                             const std::string& link, 
const trajectory_msgs::JointTrajectory& detach_posture,
 
 1044                                             touch_links, detach_posture, subframe_poses));
 
 1049   attached_bodies.clear();
 
 1052     attached_bodies.push_back(it.second.get());
 
 1057   attached_bodies.clear();
 
 1059     if (group->
hasLinkModel(it.second->getAttachedLinkName()))
 
 1060       attached_bodies.push_back(it.second.get());
 
 1065   attached_bodies.clear();
 
 1067     if (it.second->getAttachedLink() == link_model)
 
 1068       attached_bodies.push_back(it.second.get());
 
 1085     if (it->second->getAttachedLink() != link)
 
 1091     const auto del = it++;
 
 1100     if (!group->hasLinkModel(it->second->getAttachedLinkName()))
 
 1106     const auto del = it++;
 
 1135   const auto& result = 
getFrameInfo(frame_id, ignored_link, found);
 
 1138     *frame_found = found;
 
 1140     ROS_WARN_NAMED(
LOGNAME, 
"getFrameTransform() did not find a frame with name %s.", frame_id.c_str());
 
 1146                                                   bool& frame_found)
 const 
 1148   if (!frame_id.empty() && frame_id[0] == 
'/')
 
 1149     return getFrameInfo(frame_id.substr(1), robot_link, frame_found);
 
 1151   static const Eigen::Isometry3d IDENTITY_TRANSFORM = Eigen::Isometry3d::Identity();
 
 1156     return IDENTITY_TRANSFORM;
 
 1158   if ((robot_link = 
robot_model_->getLinkModel(frame_id, &frame_found)))
 
 1163   robot_link = 
nullptr;
 
 1169     const Eigen::Isometry3d& 
transform = jt->second->getGlobalPose();
 
 1170     robot_link = jt->second->getAttachedLink();
 
 1179     const Eigen::Isometry3d& 
transform = body.second->getGlobalSubframeTransform(frame_id, &frame_found);
 
 1182       robot_link = body.second->getAttachedLink();
 
 1188   robot_link = 
nullptr;
 
 1189   frame_found = 
false;
 
 1190   return IDENTITY_TRANSFORM;
 
 1195   if (!frame_id.empty() && frame_id[0] == 
'/')
 
 1203     return !it->second->getGlobalCollisionBodyTransforms().empty();
 
 1208     if (body.second->hasSubframeTransform(frame_id))
 
 1215                                  const std_msgs::ColorRGBA& color, 
const std::string& ns, 
const ros::Duration& dur,
 
 1216                                  bool include_attached)
 const 
 1218   std::size_t cur_num = arr.markers.size();
 
 1220   unsigned int id = cur_num;
 
 1221   for (std::size_t i = cur_num; i < arr.markers.size(); ++i, ++id)
 
 1223     arr.markers[i].ns = ns;
 
 1224     arr.markers[i].id = id;
 
 1225     arr.markers[i].lifetime = dur;
 
 1226     arr.markers[i].color = color;
 
 1231                                  bool include_attached)
 const 
 1234   for (
const std::string& link_name : link_names)
 
 1237     const LinkModel* link_model = 
robot_model_->getLinkModel(link_name);
 
 1240     if (include_attached)
 
 1242         if (it.second->getAttachedLink() == link_model)
 
 1244           for (std::size_t j = 0; j < it.second->getShapes().size(); ++j)
 
 1246             visualization_msgs::Marker att_mark;
 
 1247             att_mark.header.frame_id = 
robot_model_->getModelFrame();
 
 1248             att_mark.header.stamp = tm;
 
 1252               if (fabs(att_mark.scale.x * att_mark.scale.y * att_mark.scale.z) < std::numeric_limits<float>::epsilon())
 
 1254               att_mark.pose = 
tf2::toMsg(it.second->getGlobalCollisionBodyTransforms()[j]);
 
 1255               arr.markers.push_back(att_mark);
 
 1260     if (link_model->getShapes().empty())
 
 1263     for (std::size_t j = 0; j < link_model->getShapes().size(); ++j)
 
 1265       visualization_msgs::Marker mark;
 
 1267       mark.header.stamp = tm;
 
 1270       const std::string& mesh_resource = link_model->getVisualMeshFilename();
 
 1271       if (mesh_resource.empty() || link_model->getShapes().size() > 1)
 
 1276         if (fabs(mark.scale.x * mark.scale.y * mark.scale.z) < std::numeric_limits<float>::epsilon())
 
 1283         mark.type = mark.MESH_RESOURCE;
 
 1284         mark.mesh_use_embedded_materials = 
false;
 
 1285         mark.mesh_resource = mesh_resource;
 
 1288         mark.scale.x = mesh_scale[0];
 
 1289         mark.scale.y = mesh_scale[1];
 
 1290         mark.scale.z = mesh_scale[2];
 
 1294       arr.markers.push_back(mark);
 
 1302   Eigen::MatrixXd result;
 
 1303   if (!
getJacobian(group, group->getLinkModels().back(), reference_point_position, result, 
false))
 
 1304     throw Exception(
"Unable to compute Jacobian");
 
 1309                              const Eigen::Vector3d& reference_point_position, Eigen::MatrixXd& jacobian,
 
 1310                              bool use_quaternion_representation)
 const 
 1314   if (!group->isChain())
 
 1316     ROS_ERROR_NAMED(
LOGNAME, 
"The group '%s' is not a chain. Cannot compute Jacobian.", group->getName().c_str());
 
 1320   if (!group->isLinkUpdated(link->getName()))
 
 1322     ROS_ERROR_NAMED(
LOGNAME, 
"Link name '%s' does not exist in the chain '%s' or is not a child for this chain",
 
 1323                     link->getName().c_str(), group->getName().c_str());
 
 1330   Eigen::Isometry3d reference_transform =
 
 1332   int rows = use_quaternion_representation ? 7 : 6;
 
 1333   int columns = group->getVariableCount();
 
 1334   jacobian = Eigen::MatrixXd::Zero(rows, columns);
 
 1338   Eigen::Vector3d point_transform = link_transform * reference_point_position;
 
 1348   Eigen::Isometry3d joint_transform;
 
 1359     const JointModel* pjm = link->getParentJointModel();
 
 1360     if (pjm->getVariableCount() > 0)
 
 1362       if (!group->hasJointModel(pjm->getName()))
 
 1364         link = pjm->getParentLinkModel();
 
 1367       unsigned int joint_index = group->getVariableGroupIndex(pjm->getName());
 
 1373         jacobian.block<3, 1>(0, joint_index) =
 
 1374             jacobian.block<3, 1>(0, joint_index) + joint_axis.cross(point_transform - joint_transform.translation());
 
 1375         jacobian.block<3, 1>(3, joint_index) = jacobian.block<3, 1>(3, joint_index) + joint_axis;
 
 1380         jacobian.block<3, 1>(0, joint_index) = jacobian.block<3, 1>(0, joint_index) + joint_axis;
 
 1384         joint_axis = joint_transform.linear() * 
Eigen::Vector3d(1.0, 0.0, 0.0);
 
 1385         jacobian.block<3, 1>(0, joint_index) = jacobian.block<3, 1>(0, joint_index) + joint_axis;
 
 1386         joint_axis = joint_transform.linear() * 
Eigen::Vector3d(0.0, 1.0, 0.0);
 
 1387         jacobian.block<3, 1>(0, joint_index + 1) = jacobian.block<3, 1>(0, joint_index + 1) + joint_axis;
 
 1388         joint_axis = joint_transform.linear() * 
Eigen::Vector3d(0.0, 0.0, 1.0);
 
 1389         jacobian.block<3, 1>(0, joint_index + 2) = jacobian.block<3, 1>(0, joint_index + 2) +
 
 1390                                                    joint_axis.cross(point_transform - joint_transform.translation());
 
 1391         jacobian.block<3, 1>(3, joint_index + 2) = jacobian.block<3, 1>(3, joint_index + 2) + joint_axis;
 
 1396     if (pjm == root_joint_model)
 
 1398     link = pjm->getParentLinkModel();
 
 1400   if (use_quaternion_representation)
 
 1407     Eigen::Quaterniond q(link_transform.linear());
 
 1408     double w = q.w(), 
x = q.x(), 
y = q.y(), 
z = q.z();
 
 1409     Eigen::MatrixXd quaternion_update_matrix(4, 3);
 
 1410     quaternion_update_matrix << -
x, -
y, -
z, w, -
z, 
y, 
z, w, -
x, -
y, 
x, w;
 
 1411     jacobian.block(3, 0, 4, columns) = 0.5 * quaternion_update_matrix * jacobian.block(3, 0, 3, columns);
 
 1417                                        const Eigen::Vector3d& reference_point_position, Eigen::MatrixXd& jacobian,
 
 1418                                        Eigen::MatrixXd& jacobian_derivative)
 const 
 1421   const int columns = group->getVariableCount();
 
 1422   jacobian_derivative.setZero(rows, columns);
 
 1425   if (!
getJacobian(group, link, reference_point_position, jacobian, 
false))
 
 1435     const JointModel* pjm = link->getParentJointModel();
 
 1436     if (pjm->getVariableCount() > 0)
 
 1438       if (!group->hasJointModel(pjm->getName()))
 
 1440         link = pjm->getParentLinkModel();
 
 1443       unsigned int current_joint_index = group->getVariableGroupIndex(pjm->getName());
 
 1447         for (
unsigned int pd_joint_index = 0; pd_joint_index < group->getVariableCount(); pd_joint_index++)
 
 1449           jacobian_derivative.col(current_joint_index) +=
 
 1451               velocities[pd_joint_index];
 
 1457     if (pjm == group->getJointModels()[0])
 
 1459     link = pjm->getParentLinkModel();
 
 1465                                                                            int column_index, 
int joint_index)
 
 1468   const Eigen::Matrix<double, 6, 1>& jac_j = jacobian.col(joint_index);
 
 1469   const Eigen::Matrix<double, 6, 1>& jac_i = jacobian.col(column_index);
 
 1471   Eigen::Matrix<double, 6, 1> t_djdq = Eigen::Matrix<double, 6, 1>::Zero();
 
 1473   if (joint_index <= column_index)
 
 1477     t_djdq.segment<3>(0) = jac_j_angular.cross(jac_i.segment<3>(0));
 
 1478     t_djdq.segment<3>(3) = jac_j_angular.cross(jac_i.segment<3>(3));
 
 1480   else if (joint_index > column_index)
 
 1483     t_djdq.segment<3>(0) = -jac_j.segment<3>(0).cross(jac_i.segment<3>(3));
 
 1491   Eigen::VectorXd qdot;
 
 1499   Eigen::Matrix<double, 6, 1> 
t;
 
 1505                                          const Eigen::VectorXd& twist, 
const LinkModel* tip)
 const 
 1508   Eigen::MatrixXd j(6, jmg->getVariableCount());
 
 1514   Eigen::MatrixXd e_wb = Eigen::ArrayXXd::Zero(6, 6);
 
 1515   e_wb.block(0, 0, 3, 3) = e_mb.matrix().block(0, 0, 3, 3);
 
 1516   e_wb.block(3, 3, 3, 3) = e_mb.matrix().block(0, 0, 3, 3);
 
 1520   Eigen::JacobiSVD<Eigen::MatrixXd> svd_of_j(j, Eigen::ComputeThinU | Eigen::ComputeThinV);
 
 1521   const Eigen::MatrixXd& u = svd_of_j.matrixU();
 
 1522   const Eigen::MatrixXd& v = svd_of_j.matrixV();
 
 1523   const Eigen::VectorXd& 
s = svd_of_j.singularValues();
 
 1525   Eigen::VectorXd sinv = 
s;
 
 1526   static const double PINVTOLER = std::numeric_limits<float>::epsilon();
 
 1528   for (std::size_t i = 0; i < static_cast<std::size_t>(
s.rows()); ++i)
 
 1529     if (fabs(
s(i)) > maxsv)
 
 1531   for (std::size_t i = 0; i < static_cast<std::size_t>(
s.rows()); ++i)
 
 1534     if (fabs(
s(i)) > maxsv * PINVTOLER)
 
 1535       sinv(i) = 1.0 / 
s(i);
 
 1539   Eigen::MatrixXd jinv = (v * sinv.asDiagonal() * u.transpose());
 
 1542   qdot = jinv * twist;
 
 1548   Eigen::VectorXd q(jmg->getVariableCount());
 
 1556     std::vector<double> 
values;
 
 1558     return constraint(
this, jmg, &
values[0]);
 
 1574   return setFromIK(jmg, pose, solver->getTipFrame(), timeout, constraint, options);
 
 1577 bool RobotState::setFromIK(
const JointModelGroup* jmg, 
const geometry_msgs::Pose& pose, 
const std::string& tip,
 
 1581   Eigen::Isometry3d mat;
 
 1583   static std::vector<double> consistency_limits;
 
 1584   return setFromIK(jmg, mat, tip, consistency_limits, timeout, constraint, options);
 
 1587 bool RobotState::setFromIK(
const JointModelGroup* jmg, 
const Eigen::Isometry3d& pose, 
double timeout,
 
 1591   const kinematics::KinematicsBaseConstPtr& solver = jmg->getSolverInstance();
 
 1597   static std::vector<double> consistency_limits;
 
 1598   return setFromIK(jmg, pose, solver->getTipFrame(), consistency_limits, timeout, constraint, options);
 
 1601 bool RobotState::setFromIK(
const JointModelGroup* jmg, 
const Eigen::Isometry3d& pose_in, 
const std::string& tip_in,
 
 1605   static std::vector<double> consistency_limits;
 
 1606   return setFromIK(jmg, pose_in, tip_in, consistency_limits, timeout, constraint, options);
 
 1613                          const std::vector<double>& ik_sol, moveit_msgs::MoveItErrorCodes& error_code)
 
 1616   std::vector<double> solution(bij.size());
 
 1617   for (std::size_t i = 0; i < bij.size(); ++i)
 
 1618     solution[bij[i]] = ik_sol[i];
 
 1619   if (constraint(state, group, &solution[0]))
 
 1620     error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
 
 1637         getLinkModel((!ik_frame.empty() && ik_frame[0] == 
'/') ? ik_frame.substr(1) : ik_frame);
 
 1648 bool RobotState::setFromIK(
const JointModelGroup* jmg, 
const Eigen::Isometry3d& pose_in, 
const std::string& tip_in,
 
 1649                            const std::vector<double>& consistency_limits_in, 
double timeout,
 
 1655   poses.push_back(pose_in);
 
 1657   std::vector<std::string> tips;
 
 1658   tips.push_back(tip_in);
 
 1660   std::vector<std::vector<double> > consistency_limits;
 
 1661   consistency_limits.push_back(consistency_limits_in);
 
 1663   return setFromIK(jmg, poses, tips, consistency_limits, timeout, constraint, options);
 
 1667                            const std::vector<std::string>& tips_in, 
double timeout,
 
 1671   const std::vector<std::vector<double> > consistency_limits;
 
 1672   return setFromIK(jmg, poses_in, tips_in, consistency_limits, timeout, constraint, options);
 
 1676                            const std::vector<std::string>& tips_in,
 
 1677                            const std::vector<std::vector<double> >& consistency_limit_sets, 
double timeout,
 
 1682   if (poses_in.size() != tips_in.size())
 
 1692   bool valid_solver = 
true;
 
 1695     valid_solver = 
false;
 
 1698   else if (poses_in.size() > 1)
 
 1700     std::string error_msg;
 
 1701     if (!solver->supportsGroup(jmg, &error_msg))
 
 1706                       typeid(solver_ref).
name(), jmg->
getName().c_str(), error_msg.c_str());
 
 1707       valid_solver = 
false;
 
 1714     if (poses_in.size() > 1)
 
 1717       return setFromIKSubgroups(jmg, poses_in, tips_in, consistency_limit_sets, timeout, constraint, options);
 
 1727   std::vector<double> consistency_limits;
 
 1728   if (consistency_limit_sets.size() > 1)
 
 1731                     "Invalid number (%zu) of sets of consistency limits for a setFromIK request " 
 1732                     "that is being solved by a single IK solver",
 
 1733                     consistency_limit_sets.size());
 
 1736   else if (consistency_limit_sets.size() == 1)
 
 1737     consistency_limits = consistency_limit_sets[0];
 
 1742   const std::vector<std::string>& solver_tip_frames = solver->getTipFrames();
 
 1745   std::vector<bool> tip_frames_used(solver_tip_frames.size(), 
false);
 
 1748   std::vector<geometry_msgs::Pose> ik_queries(solver_tip_frames.size());
 
 1751   for (std::size_t i = 0; i < poses_in.size(); ++i)
 
 1754     Eigen::Isometry3d pose = poses_in[i];
 
 1755     std::string pose_frame = tips_in[i];
 
 1758     if (!pose_frame.empty() && pose_frame[0] == 
'/')
 
 1759       pose_frame = pose_frame.substr(1);
 
 1766     bool found_valid_frame = 
false;
 
 1767     std::size_t solver_tip_id;  
 
 1768     for (solver_tip_id = 0; solver_tip_id < solver_tip_frames.size(); ++solver_tip_id)
 
 1771       if (tip_frames_used[solver_tip_id])
 
 1775       std::string solver_tip_frame = solver_tip_frames[solver_tip_id];
 
 1779       if (!solver_tip_frame.empty() && solver_tip_frame[0] == 
'/')
 
 1780         solver_tip_frame = solver_tip_frame.substr(1);
 
 1782       if (pose_frame != solver_tip_frame)
 
 1784         Eigen::Isometry3d pose_parent_to_frame;
 
 1791         Eigen::Isometry3d tip_parent_to_tip;
 
 1798         if (pose_parent == tip_parent)
 
 1801           pose = pose * pose_parent_to_frame.inverse() * tip_parent_to_tip;
 
 1802           found_valid_frame = 
true;
 
 1808         found_valid_frame = 
true;
 
 1814     if (!found_valid_frame)
 
 1816       ROS_ERROR_NAMED(
LOGNAME, 
"Cannot compute IK for query %zu pose reference frame '%s'", i, pose_frame.c_str());
 
 1818       std::stringstream ss;
 
 1819       for (solver_tip_id = 0; solver_tip_id < solver_tip_frames.size(); ++solver_tip_id)
 
 1820         ss << solver_tip_frames[solver_tip_id] << 
", ";
 
 1826     tip_frames_used[solver_tip_id] = 
true;
 
 1829     geometry_msgs::Pose ik_query;
 
 1833     ik_queries[solver_tip_id] = ik_query;
 
 1837   for (std::size_t solver_tip_id = 0; solver_tip_id < solver_tip_frames.size(); ++solver_tip_id)
 
 1840     if (tip_frames_used[solver_tip_id])
 
 1844     std::string solver_tip_frame = solver_tip_frames[solver_tip_id];
 
 1848     if (!solver_tip_frame.empty() && solver_tip_frame[0] == 
'/')
 
 1849       solver_tip_frame = solver_tip_frame.substr(1);
 
 1859     geometry_msgs::Pose ik_query;
 
 1863     ik_queries[solver_tip_id] = ik_query;
 
 1866     tip_frames_used[solver_tip_id] = 
true;
 
 1870   if (timeout < std::numeric_limits<double>::epsilon())
 
 1876     ik_callback_fn = [
this, jmg, constraint](
const geometry_msgs::Pose& pose, 
const std::vector<double>& joints,
 
 1877                                              moveit_msgs::MoveItErrorCodes& error_code) {
 
 1878       ikCallbackFnAdapter(
this, jmg, constraint, pose, joints, error_code);
 
 1884   std::vector<double> initial_values;
 
 1886   std::vector<double> seed(bij.size());
 
 1887   for (std::size_t i = 0; i < bij.size(); ++i)
 
 1888     seed[i] = initial_values[bij[i]];
 
 1891   std::vector<double> ik_sol;
 
 1892   moveit_msgs::MoveItErrorCodes error;
 
 1894   if (solver->searchPositionIK(ik_queries, seed, timeout, consistency_limits, ik_sol, ik_callback_fn, error, options,
 
 1897     std::vector<double> solution(bij.size());
 
 1898     for (std::size_t i = 0; i < bij.size(); ++i)
 
 1899       solution[bij[i]] = ik_sol[i];
 
 1907                                     const std::vector<std::string>& tips_in,
 
 1908                                     const std::vector<std::vector<double> >& consistency_limits, 
double timeout,
 
 1915   std::vector<const JointModelGroup*> sub_groups;
 
 1916   jmg->getSubgroups(sub_groups);
 
 1919   if (poses_in.size() != sub_groups.size())
 
 1921     ROS_ERROR_NAMED(
LOGNAME, 
"Number of poses (%zu) must be the same as number of sub-groups (%zu)", poses_in.size(),
 
 1926   if (tips_in.size() != sub_groups.size())
 
 1928     ROS_ERROR_NAMED(
LOGNAME, 
"Number of tip names (%zu) must be same as number of sub-groups (%zu)", tips_in.size(),
 
 1933   if (!consistency_limits.empty() && consistency_limits.size() != sub_groups.size())
 
 1935     ROS_ERROR_NAMED(
LOGNAME, 
"Number of consistency limit vectors must be the same as number of sub-groups");
 
 1939   for (std::size_t i = 0; i < consistency_limits.size(); ++i)
 
 1943       ROS_ERROR_NAMED(
LOGNAME, 
"Number of joints in consistency_limits[%zu] is %zu but it should be should be %u", i,
 
 1950   std::vector<kinematics::KinematicsBaseConstPtr> solvers;
 
 1951   for (std::size_t i = 0; i < poses_in.size(); ++i)
 
 1953     kinematics::KinematicsBaseConstPtr solver = sub_groups[i]->getSolverInstance();
 
 1959     solvers.push_back(solver);
 
 1964   std::vector<std::string> pose_frames = tips_in;
 
 1967   for (std::size_t i = 0; i < poses_in.size(); ++i)
 
 1970     Eigen::Isometry3d& pose = transformed_poses[i];
 
 1971     std::string& pose_frame = pose_frames[i];
 
 1978     std::string solver_tip_frame = solvers[i]->getTipFrame();
 
 1982     if (!solver_tip_frame.empty() && solver_tip_frame[0] == 
'/')
 
 1983       solver_tip_frame = solver_tip_frame.substr(1);
 
 1985     if (pose_frame != solver_tip_frame)
 
 1990         pose_frame = body->getAttachedLinkName();
 
 1991         pose = pose * body->getPose().inverse();  
 
 1993       if (pose_frame != solver_tip_frame)
 
 2000         for (
const std::pair<const LinkModel* const, Eigen::Isometry3d>& fixed_link : fixed_links)
 
 2001           if (fixed_link.first->getName() == solver_tip_frame)
 
 2003             pose_frame = solver_tip_frame;
 
 2004             pose = pose * fixed_link.second;  
 
 2010     if (pose_frame != solver_tip_frame)
 
 2013                       pose_frame.c_str(), solver_tip_frame.c_str());
 
 2019   std::vector<geometry_msgs::Pose> ik_queries(poses_in.size());
 
 2020   for (std::size_t i = 0; i < transformed_poses.size(); ++i)
 
 2022     Eigen::Quaterniond quat(transformed_poses[i].linear());
 
 2024     ik_queries[i].position.x = 
point.x();
 
 2025     ik_queries[i].position.y = 
point.y();
 
 2026     ik_queries[i].position.z = 
point.z();
 
 2027     ik_queries[i].orientation.x = quat.x();
 
 2028     ik_queries[i].orientation.y = quat.y();
 
 2029     ik_queries[i].orientation.z = quat.z();
 
 2030     ik_queries[i].orientation.w = quat.w();
 
 2034   if (timeout < std::numeric_limits<double>::epsilon())
 
 2035     timeout = jmg->getDefaultIKTimeout();
 
 2039   bool first_seed = 
true;
 
 2040   unsigned int attempts = 0;
 
 2045     bool found_solution = 
true;
 
 2046     for (std::size_t sg = 0; sg < sub_groups.size(); ++sg)
 
 2048       const std::vector<unsigned int>& bij = sub_groups[sg]->getKinematicsSolverJointBijection();
 
 2049       std::vector<double> seed(bij.size());
 
 2053         std::vector<double> initial_values;
 
 2055         for (std::size_t i = 0; i < bij.size(); ++i)
 
 2056           seed[i] = initial_values[bij[i]];
 
 2062         std::vector<double> random_values;
 
 2063         sub_groups[sg]->getVariableRandomPositions(rng, random_values);
 
 2064         for (std::size_t i = 0; i < bij.size(); ++i)
 
 2065           seed[i] = random_values[bij[i]];
 
 2069       std::vector<double> ik_sol;
 
 2070       moveit_msgs::MoveItErrorCodes error;
 
 2071       const std::vector<double>& climits = consistency_limits.empty() ? std::vector<double>() : consistency_limits[sg];
 
 2072       if (solvers[sg]->searchPositionIK(ik_queries[sg], seed, (timeout - elapsed) / sub_groups.size(), climits, ik_sol,
 
 2075         std::vector<double> solution(bij.size());
 
 2076         for (std::size_t i = 0; i < bij.size(); ++i)
 
 2077           solution[bij[i]] = ik_sol[i];
 
 2082         found_solution = 
false;
 
 2088       std::vector<double> full_solution;
 
 2090       if (constraint ? constraint(
this, jmg, &full_solution[0]) : 
true)
 
 2098   } 
while (elapsed < timeout);
 
 2106   core::AABB bounding_box;
 
 2107   std::vector<const LinkModel*> links = 
robot_model_->getLinkModelsWithCollisionGeometry();
 
 2108   for (
const LinkModel* link : links)
 
 2112     transform.translate(link->getCenteredBoundingBoxOffset());
 
 2113     bounding_box.extendWithTransformedBox(transform, extents);
 
 2118     const std::vector<shapes::ShapeConstPtr>& 
shapes = it.second->getShapes();
 
 2119     for (std::size_t i = 0; i < transforms.size(); ++i)
 
 2122       bounding_box.extendWithTransformedBox(transforms[i], extents);
 
 2127   aabb.resize(6, 0.0);
 
 2128   if (!bounding_box.isEmpty())
 
 2132     Eigen::Map<Eigen::VectorXd, Eigen::Unaligned, Eigen::InnerStride<2> >(
aabb.data(), 3) = bounding_box.min();
 
 2133     Eigen::Map<Eigen::VectorXd, Eigen::Unaligned, Eigen::InnerStride<2> >(
aabb.data() + 1, 3) = bounding_box.max();
 
 2139   const std::vector<std::string>& nm = 
robot_model_->getVariableNames();
 
 2140   for (std::size_t i = 0; i < nm.size(); ++i)
 
 2141     out << nm[i] << 
"=" << 
position_[i] << std::endl;
 
 2152   for (
const JointModel* joint : joints)
 
 2155     if (joint->getVariableCount() > 1)
 
 2168     out << 
"   " << std::fixed << std::setprecision(5) << 
bound.min_position_ << 
"\t";
 
 2169     double delta = 
bound.max_position_ - 
bound.min_position_;
 
 2170     double step = delta / 20.0;
 
 2172     bool marker_shown = 
false;
 
 2173     for (
double value = 
bound.min_position_; value < 
bound.max_position_; value += step)
 
 2176       if (!marker_shown && current_value < value)
 
 2179         marker_shown = 
true;
 
 2188     out << 
" \t" << std::fixed << std::setprecision(5) << 
bound.max_position_ << 
"  \t" << joint->getName()
 
 2189         << 
" current: " << std::fixed << std::setprecision(5) << current_value << std::endl;
 
 2198   out << 
"  * Dirty Joint Transforms: " << std::endl;
 
 2199   const std::vector<const JointModel*>& jm = 
robot_model_->getJointModels();
 
 2200   for (
const JointModel* joint : jm)
 
 2202       out << 
"    " << joint->getName() << std::endl;
 
 2205   out << 
"  * Dirty Collision Body Transforms: " 
 2211   out << 
"Robot State @" << 
this << std::endl;
 
 2216     out << 
"  * Position: ";
 
 2217     for (std::size_t i = 0; i < n; ++i)
 
 2222     out << 
"  * Position: NULL" << std::endl;
 
 2226     out << 
"  * Velocity: ";
 
 2227     for (std::size_t i = 0; i < n; ++i)
 
 2232     out << 
"  * Velocity: NULL" << std::endl;
 
 2236     out << 
"  * Acceleration: ";
 
 2237     for (std::size_t i = 0; i < n; ++i)
 
 2242     out << 
"  * Acceleration: NULL" << std::endl;
 
 2246   out << 
"  * Dirty Collision Body Transforms: " 
 2254   if (
checkIsometry(transform, CHECK_ISOMETRY_PRECISION, 
false))
 
 2256     Eigen::Quaterniond q(
transform.linear());
 
 2257     out << 
"T.xyz = [" << 
transform.translation().x() << 
", " << 
transform.translation().y() << 
", " 
 2258         << 
transform.translation().z() << 
"], Q.xyzw = [" << q.x() << 
", " << q.y() << 
", " << q.z() << 
", " << q.w()
 
 2263     out << 
"[NON-ISOMETRY] " 
 2265                Eigen::IOFormat(Eigen::StreamPrecision, Eigen::DontAlignCols, 
", ", 
"; ", 
"", 
"", 
"[", 
"]"));
 
 2274     out << 
"No transforms computed" << std::endl;
 
 2278   out << 
"Joint transforms:" << std::endl;
 
 2279   const std::vector<const JointModel*>& jm = 
robot_model_->getJointModels();
 
 2285     out << 
"  " << joint->getName();
 
 2286     const int idx = joint->getJointIndex();
 
 2293   out << 
"Link poses:" << std::endl;
 
 2294   const std::vector<const LinkModel*>& link_model = 
robot_model_->getLinkModels();
 
 2295   for (
const LinkModel* link : link_model)
 
 2297     out << 
"  " << link->getName() << 
": ";
 
 2304   std::stringstream ss;
 
 2305   ss << 
"ROBOT: " << 
robot_model_->getName() << std::endl;
 
 2312 void getPoseString(std::ostream& ss, 
const Eigen::Isometry3d& pose, 
const std::string& pfx)
 
 2315   for (
int y = 0; 
y < 4; ++
y)
 
 2318     for (
int x = 0; 
x < 4; ++
x)
 
 2320       ss << std::setw(8) << pose(
y, 
x) << 
" ";
 
 2330   std::string pfx = pfx0 + 
"+--";
 
 2332   ss << pfx << 
"Joint: " << jm->getName() << std::endl;
 
 2334   pfx = pfx0 + (last ? 
"   " : 
"|  ");
 
 2336   for (std::size_t i = 0; i < jm->getVariableCount(); ++i)
 
 2339     ss << pfx << jm->getVariableNames()[i] << std::setw(12) << 
position_[jm->getFirstVariableIndex() + i] << std::endl;
 
 2342   const LinkModel* link_model = jm->getChildLinkModel();
 
 2344   ss << pfx << 
"Link: " << link_model->
getName() << std::endl;
 
 2352   for (std::vector<const JointModel*>::const_iterator it = link_model->
getChildJointModels().begin();
 
 2357 std::ostream& 
operator<<(std::ostream& out, 
const RobotState& s)
 
 2359   s.printStateInfo(out);
 
 2365   std::vector<const moveit::core::AttachedBody*> left_attached;
 
 2366   std::vector<const moveit::core::AttachedBody*> right_attached;
 
 2367   left.getAttachedBodies(left_attached);
 
 2368   right.getAttachedBodies(right_attached);
 
 2369   if (left_attached.size() != right_attached.size())
 
 2377     auto it = std::find_if(right_attached.cbegin(), right_attached.cend(),
 
 2379                              return object->getName() == left_object->getName();
 
 2381     if (it == right_attached.cend())
 
 2387     if (left_object->getAttachedLink() != right_object->
getAttachedLink())
 
 2389       ROS_DEBUG_STREAM(prefix << 
"different attach links: " << left_object->getName() << 
" attached to " 
 2393     if (left_object->getShapes().size() != right_object->
getShapes().size())
 
 2395       ROS_DEBUG_STREAM(prefix << 
"different object shapes: " << left_object->getName());
 
 2399     auto left_it = left_object->getShapePosesInLinkFrame().cbegin();
 
 2400     auto left_end = left_object->getShapePosesInLinkFrame().cend();
 
 2402     for (; left_it != left_end; ++left_it, ++right_it)
 
 2403       if (!(left_it->matrix() - right_it->matrix()).isZero(1e-4))
 
 2405         ROS_DEBUG_STREAM(prefix << 
"different pose of attached object shape: " << left_object->getName());