47 #include <boost/bind.hpp>
54 const std::string
LOGNAME =
"robot_state";
58 , has_velocity_(false)
59 , has_acceleration_(false)
61 , dirty_link_transforms_(robot_model_->getRootJoint())
62 , dirty_collision_body_transforms_(nullptr)
71 robot_model_ = other.robot_model_;
86 static_assert((
sizeof(Eigen::Isometry3d) / EIGEN_MAX_ALIGN_BYTES) * EIGEN_MAX_ALIGN_BYTES ==
sizeof(Eigen::Isometry3d),
87 "sizeof(Eigen::Isometry3d) should be a multiple of EIGEN_MAX_ALIGN_BYTES");
89 constexpr
unsigned int extra_alignment_bytes = EIGEN_MAX_ALIGN_BYTES - 1;
91 const int nr_doubles_for_dirty_joint_transforms =
92 1 +
robot_model_->getJointModelCount() / (
sizeof(double) /
sizeof(
unsigned char));
96 sizeof(
double) * (
robot_model_->getVariableCount() * 3 + nr_doubles_for_dirty_joint_transforms) +
97 extra_alignment_bytes;
117 const int nr_doubles_for_dirty_joint_transforms =
118 1 +
robot_model_->getJointModelCount() / (
sizeof(double) /
sizeof(
unsigned char));
156 const int nr_doubles_for_dirty_joint_transforms =
157 1 +
robot_model_->getJointModelCount() / (
sizeof(double) /
sizeof(
unsigned char));
164 nr_doubles_for_dirty_joint_transforms);
170 for (
const std::pair<const std::string, AttachedBody*>& it : other.
attached_body_map_)
171 attachBody(it.second->getName(), it.second->getShapes(), it.second->getFixedTransforms(),
172 it.second->getTouchLinks(), it.second->getAttachedLinkName(), it.second->getDetachPosture(),
173 it.second->getSubframeTransforms());
295 joint->getVariableRandomPositions(rng,
position_ + joint->getFirstVariableIndex());
300 const std::vector<double>& distances)
306 assert(distances.size() == joints.size());
307 for (std::size_t i = 0; i < joints.size(); ++i)
309 const int idx = joints[i]->getFirstVariableIndex();
310 joints[i]->getVariableRandomPositionsNearBy(rng,
position_ + joints[i]->getFirstVariableIndex(),
324 const int idx = joint->getFirstVariableIndex();
325 joint->getVariableRandomPositionsNearBy(rng,
position_ + joint->getFirstVariableIndex(), near.
position_ + idx,
333 std::map<std::string, double> m;
362 for (
const std::pair<const std::string, double>& it : variable_map)
373 std::vector<std::string>& missing_variables)
const
375 missing_variables.clear();
376 const std::vector<std::string>& nm =
robot_model_->getVariableNames();
377 for (
const std::string& variable_name : nm)
378 if (variable_map.find(variable_name) == variable_map.end())
379 if (
robot_model_->getJointOfVariable(variable_name)->getMimic() ==
nullptr)
380 missing_variables.push_back(variable_name);
384 std::vector<std::string>& missing_variables)
391 const std::vector<double>& variable_position)
393 for (std::size_t i = 0; i < variable_names.size(); ++i)
406 for (
const std::pair<const std::string, double>& it : variable_map)
411 std::vector<std::string>& missing_variables)
418 const std::vector<double>& variable_velocity)
421 assert(variable_names.size() == variable_velocity.size());
422 for (std::size_t i = 0; i < variable_names.size(); ++i)
429 for (
const std::pair<const std::string, double>& it : variable_map)
434 std::vector<std::string>& missing_variables)
441 const std::vector<double>& variable_acceleration)
444 assert(variable_names.size() == variable_acceleration.size());
445 for (std::size_t i = 0; i < variable_names.size(); ++i)
452 for (
const std::pair<const std::string, double>& it : variable_map)
457 std::vector<std::string>& missing_variables)
464 const std::vector<double>& variable_effort)
467 assert(variable_names.size() == variable_effort.size());
468 for (std::size_t i = 0; i < variable_names.size(); ++i)
490 memcpy(
effort_ + joint->getFirstVariableIndex(), effort, joint->getVariableCount() *
sizeof(
double));
500 for (std::size_t i = 0; i < il.size(); ++i)
509 for (std::size_t i = 0; i < il.size(); ++i)
520 for (std::size_t i = 0; i < il.size(); ++i)
528 for (std::size_t i = 0; i < il.size(); ++i)
540 for (std::size_t i = 0; i < il.size(); ++i)
548 const std::vector<int>& il = group->getVariableIndexList();
549 for (std::size_t i = 0; i < il.size(); ++i)
559 for (std::size_t i = 0; i < il.size(); ++i)
567 for (std::size_t i = 0; i < il.size(); ++i)
574 const std::vector<int>& il = group->getVariableIndexList();
575 if (group->isContiguousWithinState())
576 memcpy(
acceleration_ + il[0], gstate, group->getVariableCount() *
sizeof(
double));
579 for (std::size_t i = 0; i < il.size(); ++i)
587 const std::vector<int>& il = group->getVariableIndexList();
588 for (std::size_t i = 0; i < il.size(); ++i)
598 for (std::size_t i = 0; i < il.size(); ++i)
606 for (std::size_t i = 0; i < il.size(); ++i)
635 const EigenSTL::vector_Isometry3d& ot = link->getCollisionOriginTransforms();
636 const std::vector<int>& ot_id = link->areCollisionOriginTransformsIdentity();
637 const int index_co = link->getFirstCollisionBodyTransformIndex();
638 const int index_l = link->getLinkIndex();
639 for (std::size_t j = 0, end = ot.size(); j != end; ++j)
667 for (
const LinkModel* link :
start->getDescendantLinkModels())
669 int idx_link = link->getLinkIndex();
674 if (link->parentJointIsFixed())
679 if (link->jointOriginTransformIsIdentity())
690 if (link->jointOriginTransformIsIdentity())
694 link->getJointOriginTransform().affine() *
getJointTransform(link->getParentJointModel()).matrix();
699 for (std::map<std::string, AttachedBody*>::const_iterator it =
attached_body_map_.begin();
718 const std::vector<const JointModel*>& cj = link->getChildJointModels();
729 child_link = parent_link;
751 for (std::map<std::string, AttachedBody*>::const_iterator it =
attached_body_map_.begin();
758 const std::vector<const JointModel*>& jm =
robot_model_->getActiveJointModels();
759 for (
const JointModel* joint : jm)
767 const std::vector<const JointModel*>& jm = group->getActiveJointModels();
768 for (
const JointModel* joint : jm)
776 const std::vector<const JointModel*>& jm =
robot_model_->getActiveJointModels();
783 const std::vector<const JointModel*>& jm = joint_group->getActiveJointModels();
784 for (
const JointModel* joint : jm)
790 for (
const JointModel* jm :
robot_model_->getActiveJointModels())
796 for (
const JointModel* jm : joint_group->getActiveJointModels())
810 std::pair<double, const JointModel*>
813 double distance = std::numeric_limits<double>::max();
814 const JointModel*
index =
nullptr;
815 for (
const JointModel* joint : joints)
820 if (
static_cast<const RevoluteJointModel*
>(joint)->isContinuous())
825 std::vector<double> lower_bounds(bounds.size()), upper_bounds(bounds.size());
826 for (std::size_t j = 0; j < bounds.size(); ++j)
828 lower_bounds[j] = bounds[j].min_position_;
829 upper_bounds[j] = bounds[j].max_position_;
831 double new_distance = joint->distance(joint_values, &lower_bounds[0]);
837 new_distance = joint->distance(joint_values, &upper_bounds[0]);
844 return std::make_pair(
distance, index);
852 const int idx = joint_id->getFirstVariableIndex();
853 const std::vector<VariableBounds>& bounds = joint_id->getVariableBounds();
856 for (std::size_t var_id = 0; var_id < joint_id->getVariableCount(); ++var_id)
860 if (dtheta > dt * bounds[var_id].max_velocity_)
873 const int idx = joint->getFirstVariableIndex();
887 void RobotState::interpolate(
const RobotState& to,
double t, RobotState& state,
const JointModelGroup* joint_group)
const
889 const std::vector<const JointModel*>& jm = joint_group->getActiveJointModels();
890 for (
const JointModel* joint : jm)
892 const int idx = joint->getFirstVariableIndex();
893 joint->interpolate(
position_ + idx, to.position_ + idx, t, state.position_ + idx);
895 state.updateMimicJoints(joint_group);
910 std::map<std::string, AttachedBody*>::const_iterator it =
attached_body_map_.find(
id);
932 const EigenSTL::vector_Isometry3d& shape_poses,
const std::set<std::string>& touch_links,
933 const std::string& link,
const trajectory_msgs::JointTrajectory& detach_posture,
942 attached_bodies.clear();
945 attached_bodies.push_back(it.second);
950 attached_bodies.clear();
952 if (group->
hasLinkModel(it.second->getAttachedLinkName()))
953 attached_bodies.push_back(it.second);
958 attached_bodies.clear();
960 if (it.second->getAttachedLink() == link_model)
961 attached_bodies.push_back(it.second);
966 for (std::map<std::string, AttachedBody*>::const_iterator it =
attached_body_map_.begin();
981 if (it->second->getAttachedLink() != link)
989 std::map<std::string, AttachedBody*>::iterator
del = it++;
999 if (!group->hasLinkModel(it->second->getAttachedLinkName()))
1007 std::map<std::string, AttachedBody*>::iterator
del = it++;
1037 const auto& result =
getFrameInfo(frame_id, ignored_link, found);
1040 *frame_found = found;
1048 bool& frame_found)
const
1050 if (!frame_id.empty() && frame_id[0] ==
'/')
1051 return getFrameInfo(frame_id.substr(1), robot_link, frame_found);
1053 static const Eigen::Isometry3d IDENTITY_TRANSFORM = Eigen::Isometry3d::Identity();
1058 return IDENTITY_TRANSFORM;
1065 robot_link =
nullptr;
1068 std::map<std::string, AttachedBody*>::const_iterator jt =
attached_body_map_.find(frame_id);
1071 const EigenSTL::vector_Isometry3d&
tf = jt->second->getGlobalCollisionBodyTransforms();
1076 robot_link =
nullptr;
1077 frame_found =
false;
1078 return IDENTITY_TRANSFORM;
1082 "There are multiple geometries associated to attached body '%s'. "
1083 "Returning the transform for the first one.",
1085 robot_link = jt->second->getAttachedLink();
1094 const auto&
transform = body.second->getGlobalSubframeTransform(frame_id, &frame_found);
1097 robot_link = body.second->getAttachedLink();
1103 robot_link =
nullptr;
1104 frame_found =
false;
1105 return IDENTITY_TRANSFORM;
1110 if (!frame_id.empty() && frame_id[0] ==
'/')
1116 std::map<std::string, AttachedBody*>::const_iterator it =
attached_body_map_.find(frame_id);
1118 return !it->second->getGlobalCollisionBodyTransforms().empty();
1123 if (body.second->hasSubframeTransform(frame_id))
1130 const std_msgs::ColorRGBA& color,
const std::string& ns,
const ros::Duration& dur,
1131 bool include_attached)
const
1133 std::size_t cur_num = arr.markers.size();
1135 unsigned int id = cur_num;
1136 for (std::size_t i = cur_num; i < arr.markers.size(); ++i, ++id)
1138 arr.markers[i].ns = ns;
1139 arr.markers[i].id = id;
1140 arr.markers[i].lifetime = dur;
1141 arr.markers[i].color = color;
1146 bool include_attached)
const
1149 for (
const std::string& link_name : link_names)
1152 const LinkModel* link_model =
robot_model_->getLinkModel(link_name);
1155 if (include_attached)
1157 if (it.second->getAttachedLink() == link_model)
1159 for (std::size_t j = 0; j < it.second->getShapes().size(); ++j)
1161 visualization_msgs::Marker att_mark;
1162 att_mark.header.frame_id =
robot_model_->getModelFrame();
1163 att_mark.header.stamp = tm;
1167 if (fabs(att_mark.scale.x * att_mark.scale.y * att_mark.scale.z) < std::numeric_limits<float>::epsilon())
1169 att_mark.pose =
tf2::toMsg(it.second->getGlobalCollisionBodyTransforms()[j]);
1170 arr.markers.push_back(att_mark);
1175 if (link_model->getShapes().empty())
1178 for (std::size_t j = 0; j < link_model->getShapes().size(); ++j)
1180 visualization_msgs::Marker mark;
1182 mark.header.stamp = tm;
1185 const std::string& mesh_resource = link_model->getVisualMeshFilename();
1186 if (mesh_resource.empty() || link_model->getShapes().size() > 1)
1191 if (fabs(mark.scale.x * mark.scale.y * mark.scale.z) < std::numeric_limits<float>::epsilon())
1198 mark.type = mark.MESH_RESOURCE;
1199 mark.mesh_use_embedded_materials =
false;
1200 mark.mesh_resource = mesh_resource;
1203 mark.scale.x = mesh_scale[0];
1204 mark.scale.y = mesh_scale[1];
1205 mark.scale.z = mesh_scale[2];
1209 arr.markers.push_back(mark);
1217 Eigen::MatrixXd result;
1218 if (!
getJacobian(group, group->getLinkModels().back(), reference_point_position, result,
false))
1219 throw Exception(
"Unable to compute Jacobian");
1224 const Eigen::Vector3d& reference_point_position, Eigen::MatrixXd& jacobian,
1225 bool use_quaternion_representation)
const
1229 if (!group->isChain())
1231 ROS_ERROR_NAMED(
LOGNAME,
"The group '%s' is not a chain. Cannot compute Jacobian.", group->getName().c_str());
1235 if (!group->isLinkUpdated(link->getName()))
1237 ROS_ERROR_NAMED(
LOGNAME,
"Link name '%s' does not exist in the chain '%s' or is not a child for this chain",
1238 link->getName().c_str(), group->getName().c_str());
1245 Eigen::Isometry3d reference_transform =
1247 int rows = use_quaternion_representation ? 7 : 6;
1248 int columns = group->getVariableCount();
1249 jacobian = Eigen::MatrixXd::Zero(rows, columns);
1253 Eigen::Vector3d point_transform = link_transform * reference_point_position;
1263 Eigen::Isometry3d joint_transform;
1274 const JointModel* pjm = link->getParentJointModel();
1275 if (pjm->getVariableCount() > 0)
1277 if (!group->hasJointModel(pjm->getName()))
1279 link = pjm->getParentLinkModel();
1282 unsigned int joint_index = group->getVariableGroupIndex(pjm->getName());
1288 jacobian.block<3, 1>(0, joint_index) =
1289 jacobian.block<3, 1>(0, joint_index) + joint_axis.cross(point_transform - joint_transform.translation());
1290 jacobian.block<3, 1>(3, joint_index) = jacobian.block<3, 1>(3, joint_index) + joint_axis;
1295 jacobian.block<3, 1>(0, joint_index) = jacobian.block<3, 1>(0, joint_index) + joint_axis;
1300 jacobian.block<3, 1>(0, joint_index) = jacobian.block<3, 1>(0, joint_index) + joint_axis;
1302 jacobian.block<3, 1>(0, joint_index + 1) = jacobian.block<3, 1>(0, joint_index + 1) + joint_axis;
1304 jacobian.block<3, 1>(0, joint_index + 2) = jacobian.block<3, 1>(0, joint_index + 2) +
1305 joint_axis.cross(point_transform - joint_transform.translation());
1306 jacobian.block<3, 1>(3, joint_index + 2) = jacobian.block<3, 1>(3, joint_index + 2) + joint_axis;
1311 if (pjm == root_joint_model)
1313 link = pjm->getParentLinkModel();
1315 if (use_quaternion_representation)
1322 Eigen::Quaterniond q(link_transform.linear());
1323 double w = q.w(),
x = q.x(),
y = q.y(),
z = q.z();
1324 Eigen::MatrixXd quaternion_update_matrix(4, 3);
1325 quaternion_update_matrix << -
x, -
y, -
z, w, -
z,
y,
z, w, -
x, -
y,
x, w;
1326 jacobian.block(3, 0, 4, columns) = 0.5 * quaternion_update_matrix * jacobian.block(3, 0, 3, columns);
1334 Eigen::VectorXd qdot;
1342 Eigen::Matrix<double, 6, 1>
t;
1348 const Eigen::VectorXd& twist,
const LinkModel* tip)
const
1351 Eigen::MatrixXd j(6, jmg->getVariableCount());
1357 Eigen::MatrixXd e_wb = Eigen::ArrayXXd::Zero(6, 6);
1358 e_wb.block(0, 0, 3, 3) = e_mb.matrix().block(0, 0, 3, 3);
1359 e_wb.block(3, 3, 3, 3) = e_mb.matrix().block(0, 0, 3, 3);
1363 Eigen::JacobiSVD<Eigen::MatrixXd> svd_of_j(j, Eigen::ComputeThinU | Eigen::ComputeThinV);
1364 const Eigen::MatrixXd& u = svd_of_j.matrixU();
1365 const Eigen::MatrixXd& v = svd_of_j.matrixV();
1366 const Eigen::VectorXd&
s = svd_of_j.singularValues();
1368 Eigen::VectorXd sinv =
s;
1369 static const double PINVTOLER = std::numeric_limits<float>::epsilon();
1371 for (std::size_t i = 0; i < static_cast<std::size_t>(
s.rows()); ++i)
1372 if (fabs(
s(i)) > maxsv)
1374 for (std::size_t i = 0; i < static_cast<std::size_t>(
s.rows()); ++i)
1377 if (fabs(
s(i)) > maxsv * PINVTOLER)
1378 sinv(i) = 1.0 /
s(i);
1382 Eigen::MatrixXd jinv = (v * sinv.asDiagonal() * u.transpose());
1385 qdot = jinv * twist;
1391 Eigen::VectorXd q(jmg->getVariableCount());
1399 std::vector<double>
values;
1401 return constraint(
this, jmg, &
values[0]);
1417 return setFromIK(jmg, pose, solver->getTipFrame(), timeout, constraint, options);
1420 bool RobotState::setFromIK(
const JointModelGroup* jmg,
const geometry_msgs::Pose& pose,
const std::string& tip,
1424 Eigen::Isometry3d mat;
1426 static std::vector<double> consistency_limits;
1427 return setFromIK(jmg, mat, tip, consistency_limits, timeout, constraint, options);
1430 bool RobotState::setFromIK(
const JointModelGroup* jmg,
const Eigen::Isometry3d& pose,
double timeout,
1434 const kinematics::KinematicsBaseConstPtr& solver = jmg->getSolverInstance();
1440 static std::vector<double> consistency_limits;
1441 return setFromIK(jmg, pose, solver->getTipFrame(), consistency_limits, timeout, constraint, options);
1444 bool RobotState::setFromIK(
const JointModelGroup* jmg,
const Eigen::Isometry3d& pose_in,
const std::string& tip_in,
1448 static std::vector<double> consistency_limits;
1449 return setFromIK(jmg, pose_in, tip_in, consistency_limits, timeout, constraint, options);
1456 const std::vector<double>& ik_sol, moveit_msgs::MoveItErrorCodes& error_code)
1459 std::vector<double> solution(bij.size());
1460 for (std::size_t i = 0; i < bij.size(); ++i)
1461 solution[bij[i]] = ik_sol[i];
1462 if (constraint(state, group, &solution[0]))
1463 error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
1481 getLinkModel((!ik_frame.empty() && ik_frame[0] ==
'/') ? ik_frame.substr(1) : ik_frame);
1492 bool RobotState::setFromIK(
const JointModelGroup* jmg,
const Eigen::Isometry3d& pose_in,
const std::string& tip_in,
1493 const std::vector<double>& consistency_limits_in,
double timeout,
1498 EigenSTL::vector_Isometry3d poses;
1499 poses.push_back(pose_in);
1501 std::vector<std::string> tips;
1502 tips.push_back(tip_in);
1504 std::vector<std::vector<double> > consistency_limits;
1505 consistency_limits.push_back(consistency_limits_in);
1507 return setFromIK(jmg, poses, tips, consistency_limits, timeout, constraint, options);
1511 const std::vector<std::string>& tips_in,
double timeout,
1515 const std::vector<std::vector<double> > consistency_limits;
1516 return setFromIK(jmg, poses_in, tips_in, consistency_limits, timeout, constraint, options);
1520 const std::vector<std::string>& tips_in,
1521 const std::vector<std::vector<double> >& consistency_limit_sets,
double timeout,
1526 if (poses_in.size() != tips_in.size())
1536 bool valid_solver =
true;
1539 valid_solver =
false;
1542 else if (poses_in.size() > 1)
1544 std::string error_msg;
1545 if (!solver->supportsGroup(jmg, &error_msg))
1548 typeid(*solver).name(), jmg->
getName().c_str(), error_msg.c_str());
1549 valid_solver =
false;
1556 if (poses_in.size() > 1)
1559 return setFromIKSubgroups(jmg, poses_in, tips_in, consistency_limit_sets, timeout, constraint, options);
1569 std::vector<double> consistency_limits;
1570 if (consistency_limit_sets.size() > 1)
1573 "Invalid number (%zu) of sets of consistency limits for a setFromIK request "
1574 "that is being solved by a single IK solver",
1575 consistency_limit_sets.size());
1578 else if (consistency_limit_sets.size() == 1)
1579 consistency_limits = consistency_limit_sets[0];
1581 const std::vector<std::string>& solver_tip_frames = solver->getTipFrames();
1584 std::vector<bool> tip_frames_used(solver_tip_frames.size(),
false);
1587 std::vector<geometry_msgs::Pose> ik_queries(solver_tip_frames.size());
1590 for (std::size_t i = 0; i < poses_in.size(); ++i)
1593 Eigen::Isometry3d pose = poses_in[i];
1594 std::string pose_frame = tips_in[i];
1597 if (!pose_frame.empty() && pose_frame[0] ==
'/')
1598 pose_frame = pose_frame.substr(1);
1606 bool found_valid_frame =
false;
1607 std::size_t solver_tip_id;
1608 for (solver_tip_id = 0; solver_tip_id < solver_tip_frames.size(); ++solver_tip_id)
1611 if (tip_frames_used[solver_tip_id])
1615 std::string solver_tip_frame = solver_tip_frames[solver_tip_id];
1619 if (!solver_tip_frame.empty() && solver_tip_frame[0] ==
'/')
1620 solver_tip_frame = solver_tip_frame.substr(1);
1622 if (pose_frame != solver_tip_frame)
1628 if (ab_trans.size() != 1)
1631 "with multiple geometries as a reference frame.");
1635 pose = pose * ab_trans[0].inverse();
1637 if (pose_frame != solver_tip_frame)
1646 for (
const std::pair<const LinkModel* const, Eigen::Isometry3d>& fixed_link : fixed_links)
1649 pose_frame = solver_tip_frame;
1650 pose = pose * fixed_link.second;
1658 if (pose_frame == solver_tip_frame)
1660 found_valid_frame =
true;
1667 if (!found_valid_frame)
1669 ROS_ERROR_NAMED(
LOGNAME,
"Cannot compute IK for query %zu pose reference frame '%s'", i, pose_frame.c_str());
1671 std::stringstream ss;
1672 for (solver_tip_id = 0; solver_tip_id < solver_tip_frames.size(); ++solver_tip_id)
1673 ss << solver_tip_frames[solver_tip_id] <<
", ";
1679 tip_frames_used[solver_tip_id] =
true;
1682 geometry_msgs::Pose ik_query;
1686 ik_queries[solver_tip_id] = ik_query;
1690 for (std::size_t solver_tip_id = 0; solver_tip_id < solver_tip_frames.size(); ++solver_tip_id)
1693 if (tip_frames_used[solver_tip_id])
1697 std::string solver_tip_frame = solver_tip_frames[solver_tip_id];
1701 if (!solver_tip_frame.empty() && solver_tip_frame[0] ==
'/')
1702 solver_tip_frame = solver_tip_frame.substr(1);
1712 geometry_msgs::Pose ik_query;
1716 ik_queries[solver_tip_id] = ik_query;
1719 tip_frames_used[solver_tip_id] =
true;
1723 if (timeout < std::numeric_limits<double>::epsilon())
1729 ik_callback_fn = boost::bind(&ikCallbackFnAdapter,
this, jmg, constraint, _1, _2, _3);
1734 std::vector<double> initial_values;
1736 std::vector<double> seed(bij.size());
1737 for (std::size_t i = 0; i < bij.size(); ++i)
1738 seed[i] = initial_values[bij[i]];
1741 std::vector<double> ik_sol;
1742 moveit_msgs::MoveItErrorCodes error;
1744 if (solver->searchPositionIK(ik_queries, seed, timeout, consistency_limits, ik_sol, ik_callback_fn, error, options,
1747 std::vector<double> solution(bij.size());
1748 for (std::size_t i = 0; i < bij.size(); ++i)
1749 solution[bij[i]] = ik_sol[i];
1757 const std::vector<std::string>& tips_in,
1758 const std::vector<std::vector<double> >& consistency_limits,
double timeout,
1765 std::vector<const JointModelGroup*> sub_groups;
1766 jmg->getSubgroups(sub_groups);
1769 if (poses_in.size() != sub_groups.size())
1771 ROS_ERROR_NAMED(
LOGNAME,
"Number of poses (%zu) must be the same as number of sub-groups (%zu)", poses_in.size(),
1776 if (tips_in.size() != sub_groups.size())
1778 ROS_ERROR_NAMED(
LOGNAME,
"Number of tip names (%zu) must be same as number of sub-groups (%zu)", tips_in.size(),
1783 if (!consistency_limits.empty() && consistency_limits.size() != sub_groups.size())
1785 ROS_ERROR_NAMED(
LOGNAME,
"Number of consistency limit vectors must be the same as number of sub-groups");
1789 for (std::size_t i = 0; i < consistency_limits.size(); ++i)
1793 ROS_ERROR_NAMED(
LOGNAME,
"Number of joints in consistency_limits is %zu but it should be should be %u", i,
1800 std::vector<kinematics::KinematicsBaseConstPtr> solvers;
1801 for (std::size_t i = 0; i < poses_in.size(); ++i)
1803 kinematics::KinematicsBaseConstPtr solver = sub_groups[i]->getSolverInstance();
1809 solvers.push_back(solver);
1813 EigenSTL::vector_Isometry3d transformed_poses = poses_in;
1814 std::vector<std::string> pose_frames = tips_in;
1817 for (std::size_t i = 0; i < poses_in.size(); ++i)
1820 Eigen::Isometry3d& pose = transformed_poses[i];
1821 std::string& pose_frame = pose_frames[i];
1828 std::string solver_tip_frame = solvers[i]->getTipFrame();
1832 if (!solver_tip_frame.empty() && solver_tip_frame[0] ==
'/')
1833 solver_tip_frame = solver_tip_frame.substr(1);
1835 if (pose_frame != solver_tip_frame)
1841 if (ab_trans.size() != 1)
1847 pose = pose * ab_trans[0].inverse();
1849 if (pose_frame != solver_tip_frame)
1856 for (
const std::pair<const LinkModel* const, Eigen::Isometry3d>& fixed_link : fixed_links)
1857 if (fixed_link.first->getName() == solver_tip_frame)
1859 pose_frame = solver_tip_frame;
1860 pose = pose * fixed_link.second;
1866 if (pose_frame != solver_tip_frame)
1869 pose_frame.c_str(), solver_tip_frame.c_str());
1875 std::vector<geometry_msgs::Pose> ik_queries(poses_in.size());
1878 ik_callback_fn = boost::bind(&ikCallbackFnAdapter,
this, jmg, constraint, _1, _2, _3);
1880 for (std::size_t i = 0; i < transformed_poses.size(); ++i)
1882 Eigen::Quaterniond quat(transformed_poses[i].linear());
1884 ik_queries[i].position.x =
point.x();
1885 ik_queries[i].position.y =
point.y();
1886 ik_queries[i].position.z =
point.z();
1887 ik_queries[i].orientation.x = quat.x();
1888 ik_queries[i].orientation.y = quat.y();
1889 ik_queries[i].orientation.z = quat.z();
1890 ik_queries[i].orientation.w = quat.w();
1894 if (timeout < std::numeric_limits<double>::epsilon())
1895 timeout = jmg->getDefaultIKTimeout();
1899 bool first_seed =
true;
1900 unsigned int attempts = 0;
1905 bool found_solution =
true;
1906 for (std::size_t sg = 0; sg < sub_groups.size(); ++sg)
1908 const std::vector<unsigned int>& bij = sub_groups[sg]->getKinematicsSolverJointBijection();
1909 std::vector<double> seed(bij.size());
1913 std::vector<double> initial_values;
1915 for (std::size_t i = 0; i < bij.size(); ++i)
1916 seed[i] = initial_values[bij[i]];
1922 std::vector<double> random_values;
1923 sub_groups[sg]->getVariableRandomPositions(rng, random_values);
1924 for (std::size_t i = 0; i < bij.size(); ++i)
1925 seed[i] = random_values[bij[i]];
1929 std::vector<double> ik_sol;
1930 moveit_msgs::MoveItErrorCodes error;
1931 const std::vector<double>& climits = consistency_limits.empty() ? std::vector<double>() : consistency_limits[sg];
1932 if (solvers[sg]->searchPositionIK(ik_queries[sg], seed, (timeout - elapsed) / sub_groups.size(), climits, ik_sol,
1935 std::vector<double> solution(bij.size());
1936 for (std::size_t i = 0; i < bij.size(); ++i)
1937 solution[bij[i]] = ik_sol[i];
1942 found_solution =
false;
1948 std::vector<double> full_solution;
1950 if (constraint ? constraint(
this, jmg, &full_solution[0]) :
true)
1958 }
while (elapsed < timeout);
1964 bool global_reference_frame,
double distance,
double max_step,
1970 JumpThreshold(jump_threshold_factor), validCallback, options);
1974 const LinkModel* link,
const Eigen::Isometry3d& target,
1975 bool global_reference_frame,
double max_step,
double jump_threshold_factor,
1980 MaxEEFStep(max_step), JumpThreshold(jump_threshold_factor),
1981 validCallback, options);
1985 const LinkModel* link,
const EigenSTL::vector_Isometry3d& waypoints,
1986 bool global_reference_frame,
double max_step,
double jump_threshold_factor,
1991 MaxEEFStep(max_step), JumpThreshold(jump_threshold_factor),
1992 validCallback, options);
1999 core::AABB bounding_box;
2000 std::vector<const LinkModel*> links =
robot_model_->getLinkModelsWithCollisionGeometry();
2001 for (
const LinkModel* link : links)
2005 transform.translate(link->getCenteredBoundingBoxOffset());
2006 bounding_box.extendWithTransformedBox(transform, extents);
2010 const EigenSTL::vector_Isometry3d& transforms = it.second->getGlobalCollisionBodyTransforms();
2011 const std::vector<shapes::ShapeConstPtr>&
shapes = it.second->getShapes();
2012 for (std::size_t i = 0; i < transforms.size(); ++i)
2015 bounding_box.extendWithTransformedBox(transforms[i], extents);
2020 aabb.resize(6, 0.0);
2021 if (!bounding_box.isEmpty())
2025 Eigen::Map<Eigen::VectorXd, Eigen::Unaligned, Eigen::InnerStride<2> >(
aabb.data(), 3) = bounding_box.min();
2026 Eigen::Map<Eigen::VectorXd, Eigen::Unaligned, Eigen::InnerStride<2> >(
aabb.data() + 1, 3) = bounding_box.max();
2032 const std::vector<std::string>& nm =
robot_model_->getVariableNames();
2033 for (std::size_t i = 0; i < nm.size(); ++i)
2034 out << nm[i] <<
"=" <<
position_[i] << std::endl;
2048 if (joint->getVariableCount() > 1)
2061 out <<
" " << std::fixed << std::setprecision(5) <<
bound.min_position_ <<
"\t";
2062 double delta =
bound.max_position_ -
bound.min_position_;
2063 double step = delta / 20.0;
2065 bool marker_shown =
false;
2066 for (
double value =
bound.min_position_; value <
bound.max_position_; value += step)
2069 if (!marker_shown && current_value < value)
2072 marker_shown =
true;
2081 out <<
" \t" << std::fixed << std::setprecision(5) <<
bound.max_position_ <<
" \t" << joint->getName()
2082 <<
" current: " << std::fixed << std::setprecision(5) << current_value << std::endl;
2091 out <<
" * Dirty Joint Transforms: " << std::endl;
2092 const std::vector<const JointModel*>& jm =
robot_model_->getJointModels();
2093 for (
const JointModel* joint : jm)
2095 out <<
" " << joint->getName() << std::endl;
2098 out <<
" * Dirty Collision Body Transforms: "
2104 out <<
"Robot State @" <<
this << std::endl;
2109 out <<
" * Position: ";
2110 for (std::size_t i = 0; i < n; ++i)
2115 out <<
" * Position: NULL" << std::endl;
2119 out <<
" * Velocity: ";
2120 for (std::size_t i = 0; i < n; ++i)
2125 out <<
" * Velocity: NULL" << std::endl;
2129 out <<
" * Acceleration: ";
2130 for (std::size_t i = 0; i < n; ++i)
2135 out <<
" * Acceleration: NULL" << std::endl;
2139 out <<
" * Dirty Collision Body Transforms: "
2148 Eigen::Quaterniond q(
transform.linear());
2149 out <<
"T.xyz = [" <<
transform.translation().x() <<
", " <<
transform.translation().y() <<
", "
2150 <<
transform.translation().z() <<
"], Q.xyzw = [" << q.x() <<
", " << q.y() <<
", " << q.z() <<
", " << q.w()
2151 <<
"]" << std::endl;
2158 out <<
"No transforms computed" << std::endl;
2162 out <<
"Joint transforms:" << std::endl;
2163 const std::vector<const JointModel*>& jm =
robot_model_->getJointModels();
2166 out <<
" " << joint->getName();
2167 const int idx = joint->getJointIndex();
2174 out <<
"Link poses:" << std::endl;
2175 const std::vector<const LinkModel*>& link_model =
robot_model_->getLinkModels();
2176 for (
const LinkModel* link : link_model)
2178 out <<
" " << link->getName() <<
": ";
2185 std::stringstream ss;
2186 ss <<
"ROBOT: " <<
robot_model_->getName() << std::endl;
2193 void getPoseString(std::ostream& ss,
const Eigen::Isometry3d& pose,
const std::string& pfx)
2196 for (
int y = 0;
y < 4; ++
y)
2199 for (
int x = 0;
x < 4; ++
x)
2201 ss << std::setw(8) << pose(y, x) <<
" ";
2211 std::string pfx = pfx0 +
"+--";
2213 ss << pfx <<
"Joint: " << jm->getName() << std::endl;
2215 pfx = pfx0 + (last ?
" " :
"| ");
2217 for (std::size_t i = 0; i < jm->getVariableCount(); ++i)
2220 ss << pfx << jm->getVariableNames()[i] << std::setw(12) <<
position_[jm->getFirstVariableIndex() + i] << std::endl;
2223 const LinkModel* link_model = jm->getChildLinkModel();
2225 ss << pfx <<
"Link: " << link_model->
getName() << std::endl;
2233 for (std::vector<const JointModel*>::const_iterator it = link_model->
getChildJointModels().begin();
2238 std::ostream&
operator<<(std::ostream& out,
const RobotState& s)
2240 s.printStateInfo(out);