44 #include <boost/bind.hpp> 57 const std::string
LOGNAME =
"robot_state";
60 : robot_model_(robot_model)
61 , has_velocity_(false)
62 , has_acceleration_(false)
64 , dirty_link_transforms_(robot_model_->getRootJoint())
65 , dirty_collision_body_transforms_(nullptr)
71 const int nr_doubles_for_dirty_joint_transforms =
72 1 +
robot_model_->getJointModelCount() / (
sizeof(double) /
sizeof(
unsigned char));
94 const int nr_doubles_for_dirty_joint_transforms =
95 1 +
robot_model_->getJointModelCount() / (
sizeof(double) /
sizeof(
unsigned char));
99 sizeof(
double) * (
robot_model_->getVariableCount() * 3 + nr_doubles_for_dirty_joint_transforms) + 15;
138 const int nr_doubles_for_dirty_joint_transforms =
139 1 +
robot_model_->getJointModelCount() / (
sizeof(double) /
sizeof(
unsigned char));
145 const int nr_doubles_for_dirty_joint_transforms =
146 1 +
robot_model_->getJointModelCount() / (
sizeof(double) /
sizeof(
unsigned char));
153 nr_doubles_for_dirty_joint_transforms);
159 for (std::map<std::string, AttachedBody*>::const_iterator it = other.
attached_body_map_.begin();
161 attachBody(it->second->getName(), it->second->getShapes(), it->second->getFixedTransforms(),
162 it->second->getTouchLinks(), it->second->getAttachedLinkName(), it->second->getDetachPosture());
169 ROS_WARN_NAMED(LOGNAME,
"Returning dirty joint transforms for joint '%s'", joint->
getName().c_str());
189 ROS_WARN_NAMED(LOGNAME,
"Returning dirty collision body transforms");
243 for (std::size_t i = 0; i < joints.size(); ++i)
244 joints[i]->getVariableRandomPositions(rng,
position_ + joints[i]->getFirstVariableIndex());
249 const std::vector<double>& distances)
255 assert(distances.size() == joints.size());
256 for (std::size_t i = 0; i < joints.size(); ++i)
258 const int idx = joints[i]->getFirstVariableIndex();
259 joints[i]->getVariableRandomPositionsNearBy(rng,
position_ + joints[i]->getFirstVariableIndex(),
271 for (std::size_t i = 0; i < joints.size(); ++i)
273 const int idx = joints[i]->getFirstVariableIndex();
274 joints[i]->getVariableRandomPositionsNearBy(rng,
position_ + joints[i]->getFirstVariableIndex(),
282 std::map<std::string, double> m;
311 for (std::map<std::string, double>::const_iterator it = variable_map.begin(), end = variable_map.end(); it != end;
323 std::vector<std::string>& missing_variables)
const 325 missing_variables.clear();
326 const std::vector<std::string>& nm =
robot_model_->getVariableNames();
327 for (std::size_t i = 0; i < nm.size(); ++i)
328 if (variable_map.find(nm[i]) == variable_map.end())
329 if (
robot_model_->getJointOfVariable(nm[i])->getMimic() ==
nullptr)
330 missing_variables.push_back(nm[i]);
334 std::vector<std::string>& missing_variables)
341 const std::vector<double>& variable_position)
343 for (std::size_t i = 0; i < variable_names.size(); ++i)
356 for (std::map<std::string, double>::const_iterator it = variable_map.begin(), end = variable_map.end(); it != end;
362 std::vector<std::string>& missing_variables)
369 const std::vector<double>& variable_velocity)
372 assert(variable_names.size() == variable_velocity.size());
373 for (std::size_t i = 0; i < variable_names.size(); ++i)
380 for (std::map<std::string, double>::const_iterator it = variable_map.begin(), end = variable_map.end(); it != end;
386 std::vector<std::string>& missing_variables)
393 const std::vector<double>& variable_acceleration)
396 assert(variable_names.size() == variable_acceleration.size());
397 for (std::size_t i = 0; i < variable_names.size(); ++i)
404 for (std::map<std::string, double>::const_iterator it = variable_map.begin(), end = variable_map.end(); it != end;
410 std::vector<std::string>& missing_variables)
417 const std::vector<double>& variable_effort)
420 assert(variable_names.size() == variable_effort.size());
421 for (std::size_t i = 0; i < variable_names.size(); ++i)
429 for (
size_t i = 0; i <
robot_model_->getVariableCount(); ++i)
438 ROS_ERROR_NAMED(LOGNAME,
"Unable to set joint efforts because array is being used for accelerations");
453 for (std::size_t i = 0; i < il.size(); ++i)
462 for (std::size_t i = 0; i < il.size(); ++i)
473 for (std::size_t i = 0; i < il.size(); ++i)
480 values.resize(il.size());
481 for (std::size_t i = 0; i < il.size(); ++i)
493 for (std::size_t i = 0; i < il.size(); ++i)
502 for (std::size_t i = 0; i < il.size(); ++i)
512 for (std::size_t i = 0; i < il.size(); ++i)
519 values.resize(il.size());
520 for (std::size_t i = 0; i < il.size(); ++i)
532 for (std::size_t i = 0; i < il.size(); ++i)
541 for (std::size_t i = 0; i < il.size(); ++i)
551 for (std::size_t i = 0; i < il.size(); ++i)
558 values.resize(il.size());
559 for (std::size_t i = 0; i < il.size(); ++i)
586 for (std::size_t i = 0; i < links.size(); ++i)
589 const std::vector<int>& ot_id = links[i]->areCollisionOriginTransformsIdentity();
590 const int index_co = links[i]->getFirstCollisionBodyTransformIndex();
591 const int index_l = links[i]->getLinkIndex();
592 for (std::size_t j = 0; j < ot.size(); ++j)
621 if (link->parentJointIsFixed())
626 if (link->jointOriginTransformIsIdentity())
638 if (link->jointOriginTransformIsIdentity())
642 link->getJointOriginTransform().matrix() *
getJointTransform(link->getParentJointModel()).matrix();
647 for (std::map<std::string, AttachedBody*>::const_iterator it =
attached_body_map_.begin();
667 for (std::size_t i = 0; i < cj.size(); ++i)
677 child_link = parent_link;
685 .inverse(Eigen::Isometry);
690 for (std::size_t i = 0; i < cj.size(); ++i)
699 for (std::map<std::string, AttachedBody*>::const_iterator it =
attached_body_map_.begin();
706 const std::vector<const JointModel*>& jm =
robot_model_->getActiveJointModels();
707 for (std::size_t i = 0; i < jm.size(); ++i)
716 for (std::size_t i = 0; i < jm.size(); ++i)
724 const std::vector<const JointModel*>& jm =
robot_model_->getActiveJointModels();
725 for (std::size_t i = 0; i < jm.size(); ++i)
732 for (std::size_t i = 0; i < jm.size(); ++i)
746 std::pair<double, const JointModel*>
749 double distance = std::numeric_limits<double>::max();
751 for (std::size_t i = 0; i < joints.size(); ++i)
756 if (static_cast<const RevoluteJointModel*>(joints[i])->isContinuous())
761 std::vector<double> lower_bounds(bounds.size()), upper_bounds(bounds.size());
762 for (std::size_t j = 0; j < bounds.size(); ++j)
764 lower_bounds[j] = bounds[j].min_position_;
765 upper_bounds[j] = bounds[j].max_position_;
767 double new_distance = joints[i]->distance(joint_values, &lower_bounds[0]);
768 if (new_distance < distance)
771 distance = new_distance;
773 new_distance = joints[i]->
distance(joint_values, &upper_bounds[0]);
774 if (new_distance < distance)
777 distance = new_distance;
780 return std::make_pair(distance, index);
786 for (std::size_t joint_id = 0; joint_id < jm.size(); ++joint_id)
788 const int idx = jm[joint_id]->getFirstVariableIndex();
789 const std::vector<VariableBounds>& bounds = jm[joint_id]->getVariableBounds();
792 for (std::size_t var_id = 0; var_id < jm[joint_id]->getVariableCount(); ++var_id)
796 if (dtheta > dt * bounds[var_id].max_velocity_)
808 for (std::size_t i = 0; i < jm.size(); ++i)
810 const int idx = jm[i]->getFirstVariableIndex();
811 d += jm[i]->getDistanceFactor() * jm[i]->distance(
position_ + idx, other.
position_ + idx);
828 for (std::size_t i = 0; i < jm.size(); ++i)
830 const int idx = jm[i]->getFirstVariableIndex();
848 std::map<std::string, AttachedBody*>::const_iterator it =
attached_body_map_.find(
id);
868 const std::string& link,
const trajectory_msgs::JointTrajectory& detach_posture)
880 attached_bodies.clear();
882 for (std::map<std::string, AttachedBody*>::const_iterator it =
attached_body_map_.begin();
884 attached_bodies.push_back(it->second);
890 attached_bodies.clear();
891 for (std::map<std::string, AttachedBody*>::const_iterator it =
attached_body_map_.begin();
893 if (group->
hasLinkModel(it->second->getAttachedLinkName()))
894 attached_bodies.push_back(it->second);
899 attached_bodies.clear();
900 for (std::map<std::string, AttachedBody*>::const_iterator it =
attached_body_map_.begin();
902 if (it->second->getAttachedLink() == lm)
903 attached_bodies.push_back(it->second);
908 for (std::map<std::string, AttachedBody*>::const_iterator it =
attached_body_map_.begin();
923 if (it->second->getAttachedLink() != link)
931 std::map<std::string, AttachedBody*>::iterator
del = it++;
941 if (!group->
hasLinkModel(it->second->getAttachedLinkName()))
949 std::map<std::string, AttachedBody*>::iterator
del = it++;
977 if (!
id.empty() &&
id[0] ==
'/')
981 static const Eigen::Affine3d identity_transform = Eigen::Affine3d::Identity();
983 return identity_transform;
989 std::map<std::string, AttachedBody*>::const_iterator jt =
attached_body_map_.find(
id);
992 ROS_ERROR_NAMED(LOGNAME,
"Transform from frame '%s' to frame '%s' is not known " 993 "('%s' should be a link name or an attached body id).",
994 id.c_str(),
robot_model_->getModelFrame().c_str(),
id.c_str());
995 return identity_transform;
1000 ROS_ERROR_NAMED(LOGNAME,
"Attached body '%s' has no geometry associated to it. No transform to return.",
1002 return identity_transform;
1005 ROS_DEBUG_NAMED(LOGNAME,
"There are multiple geometries associated to attached body '%s'. " 1006 "Returning the transform for the first one.",
1013 if (!
id.empty() &&
id[0] ==
'/')
1017 std::map<std::string, AttachedBody*>::const_iterator it =
attached_body_map_.find(
id);
1018 return it !=
attached_body_map_.end() && !it->second->getGlobalCollisionBodyTransforms().empty();
1022 const std_msgs::ColorRGBA& color,
const std::string& ns,
const ros::Duration& dur,
1023 bool include_attached)
const 1025 std::size_t cur_num = arr.markers.size();
1027 unsigned int id = cur_num;
1028 for (std::size_t i = cur_num; i < arr.markers.size(); ++i, ++id)
1030 arr.markers[i].ns = ns;
1031 arr.markers[i].id = id;
1032 arr.markers[i].lifetime = dur;
1033 arr.markers[i].color = color;
1038 bool include_attached)
const 1041 for (std::size_t i = 0; i < link_names.size(); ++i)
1043 ROS_DEBUG_NAMED(LOGNAME,
"Trying to get marker for link '%s'", link_names[i].c_str());
1047 if (include_attached)
1048 for (std::map<std::string, AttachedBody*>::const_iterator it =
attached_body_map_.begin();
1050 if (it->second->getAttachedLink() == lm)
1052 for (std::size_t j = 0; j < it->second->getShapes().size(); ++j)
1054 visualization_msgs::Marker att_mark;
1055 att_mark.header.frame_id =
robot_model_->getModelFrame();
1056 att_mark.header.stamp = tm;
1060 if (fabs(att_mark.scale.x * att_mark.scale.y * att_mark.scale.z) < std::numeric_limits<float>::epsilon())
1062 tf::poseEigenToMsg(it->second->getGlobalCollisionBodyTransforms()[j], att_mark.pose);
1063 arr.markers.push_back(att_mark);
1071 for (std::size_t j = 0; j < lm->
getShapes().size(); ++j)
1073 visualization_msgs::Marker mark;
1075 mark.header.stamp = tm;
1079 if (mesh_resource.empty() || lm->
getShapes().size() > 1)
1084 if (fabs(mark.scale.x * mark.scale.y * mark.scale.z) < std::numeric_limits<float>::epsilon())
1090 mark.type = mark.MESH_RESOURCE;
1091 mark.mesh_use_embedded_materials =
false;
1092 mark.mesh_resource = mesh_resource;
1095 mark.scale.x = mesh_scale[0];
1096 mark.scale.y = mesh_scale[1];
1097 mark.scale.z = mesh_scale[2];
1101 arr.markers.push_back(mark);
1107 const Eigen::Vector3d& reference_point_position)
const 1109 Eigen::MatrixXd result;
1111 throw Exception(
"Unable to compute Jacobian");
1116 const Eigen::Vector3d& reference_point_position, Eigen::MatrixXd& jacobian,
1117 bool use_quaternion_representation)
const 1123 ROS_ERROR_NAMED(LOGNAME,
"The group '%s' is not a chain. Cannot compute Jacobian.", group->
getName().c_str());
1129 ROS_ERROR_NAMED(LOGNAME,
"Link name '%s' does not exist in the chain '%s' or is not a child for this chain",
1136 Eigen::Affine3d reference_transform =
1137 root_link_model ?
getGlobalLinkTransform(root_link_model).inverse(Eigen::Isometry) : Eigen::Affine3d::Identity();
1138 int rows = use_quaternion_representation ? 7 : 6;
1140 jacobian = Eigen::MatrixXd::Zero(rows, columns);
1143 Eigen::Vector3d point_transform = link_transform * reference_point_position;
1152 Eigen::Vector3d joint_axis;
1153 Eigen::Affine3d joint_transform;
1177 jacobian.block<3, 1>(0, joint_index) =
1178 jacobian.block<3, 1>(0, joint_index) + joint_axis.cross(point_transform - joint_transform.translation());
1179 jacobian.block<3, 1>(3, joint_index) = jacobian.block<3, 1>(3, joint_index) + joint_axis;
1185 jacobian.block<3, 1>(0, joint_index) = jacobian.block<3, 1>(0, joint_index) + joint_axis;
1190 joint_axis = joint_transform * Eigen::Vector3d(1.0, 0.0, 0.0);
1191 jacobian.block<3, 1>(0, joint_index) = jacobian.block<3, 1>(0, joint_index) + joint_axis;
1192 joint_axis = joint_transform * Eigen::Vector3d(0.0, 1.0, 0.0);
1193 jacobian.block<3, 1>(0, joint_index + 1) = jacobian.block<3, 1>(0, joint_index + 1) + joint_axis;
1194 joint_axis = joint_transform * Eigen::Vector3d(0.0, 0.0, 1.0);
1195 jacobian.block<3, 1>(0, joint_index + 2) = jacobian.block<3, 1>(0, joint_index + 2) +
1196 joint_axis.cross(point_transform - joint_transform.translation());
1197 jacobian.block<3, 1>(3, joint_index + 2) = jacobian.block<3, 1>(3, joint_index + 2) + joint_axis;
1200 ROS_ERROR_NAMED(LOGNAME,
"Unknown type of joint in Jacobian computation");
1202 if (pjm == root_joint_model)
1206 if (use_quaternion_representation)
1213 Eigen::Quaterniond q(link_transform.linear());
1214 double w = q.w(),
x = q.x(),
y = q.y(),
z = q.z();
1215 Eigen::MatrixXd quaternion_update_matrix(4, 3);
1216 quaternion_update_matrix << -
x, -
y, -
z, w, -z, y, z, w, -x, -y, x, w;
1217 jacobian.block(3, 0, 4, columns) = 0.5 * quaternion_update_matrix * jacobian.block(3, 0, 3, columns);
1225 Eigen::VectorXd qdot;
1233 Eigen::Matrix<double, 6, 1> t;
1239 const Eigen::VectorXd& twist,
const LinkModel* tip)
const 1243 Eigen::Vector3d reference_point(0.0, 0.0, 0.0);
1248 Eigen::MatrixXd eWb = Eigen::ArrayXXd::Zero(6, 6);
1249 eWb.block(0, 0, 3, 3) = eMb.matrix().block(0, 0, 3, 3);
1250 eWb.block(3, 3, 3, 3) = eMb.matrix().block(0, 0, 3, 3);
1254 Eigen::JacobiSVD<Eigen::MatrixXd> svdOfJ(J, Eigen::ComputeThinU | Eigen::ComputeThinV);
1255 const Eigen::MatrixXd U = svdOfJ.matrixU();
1256 const Eigen::MatrixXd V = svdOfJ.matrixV();
1257 const Eigen::VectorXd S = svdOfJ.singularValues();
1259 Eigen::VectorXd Sinv = S;
1260 static const double pinvtoler = std::numeric_limits<float>::epsilon();
1262 for (std::size_t i = 0; i < static_cast<std::size_t>(S.rows()); ++i)
1263 if (fabs(S(i)) > maxsv)
1265 for (std::size_t i = 0; i < static_cast<std::size_t>(S.rows()); ++i)
1268 if (fabs(S(i)) > maxsv * pinvtoler)
1269 Sinv(i) = 1.0 / S(i);
1273 Eigen::MatrixXd Jinv = (V * Sinv.asDiagonal() * U.transpose());
1276 qdot = Jinv * twist;
1290 std::vector<double> values;
1292 return constraint(
this, jmg, &values[0]);
1308 return setFromIK(jmg, pose, solver->getTipFrame(), attempts, timeout, constraint, options);
1315 Eigen::Affine3d mat;
1317 static std::vector<double> consistency_limits;
1318 return setFromIK(jmg, mat, tip, consistency_limits, attempts, timeout, constraint, options);
1331 static std::vector<double> consistency_limits;
1332 return setFromIK(jmg, pose, solver->getTipFrame(), consistency_limits, attempts, timeout, constraint, options);
1339 static std::vector<double> consistency_limits;
1340 return setFromIK(jmg, pose_in, tip_in, consistency_limits, attempts, timeout, constraint, options);
1347 const std::vector<double>& ik_sol, moveit_msgs::MoveItErrorCodes& error_code)
1350 std::vector<double> solution(bij.size());
1351 for (std::size_t i = 0; i < bij.size(); ++i)
1352 solution[bij[i]] = ik_sol[i];
1353 if (constraint(state, group, &solution[0]))
1354 error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
1371 const LinkModel* lm =
getLinkModel((!ik_frame.empty() && ik_frame[0] ==
'/') ? ik_frame.substr(1) : ik_frame);
1383 const std::vector<double>& consistency_limits_in,
unsigned int attempts,
double timeout,
1389 poses.push_back(pose_in);
1391 std::vector<std::string> tips;
1392 tips.push_back(tip_in);
1394 std::vector<std::vector<double> > consistency_limits;
1395 consistency_limits.push_back(consistency_limits_in);
1397 return setFromIK(jmg, poses, tips, consistency_limits, attempts, timeout, constraint, options);
1401 const std::vector<std::string>& tips_in,
unsigned int attempts,
double timeout,
1405 static const std::vector<std::vector<double> > consistency_limits;
1406 return setFromIK(jmg, poses_in, tips_in, consistency_limits, attempts, timeout, constraint, options);
1410 const std::vector<std::string>& tips_in,
1411 const std::vector<std::vector<double> >& consistency_limit_sets,
unsigned int attempts,
1416 if (poses_in.size() != tips_in.size())
1418 ROS_ERROR_NAMED(LOGNAME,
"Number of poses must be the same as number of tips");
1426 bool valid_solver =
true;
1429 valid_solver =
false;
1432 else if (poses_in.size() > 1)
1434 std::string error_msg;
1435 if (!solver->supportsGroup(jmg, &error_msg))
1437 ROS_ERROR_NAMED(LOGNAME,
"Kinematics solver %s does not support joint group %s. Error: %s",
1438 typeid(*solver).name(), jmg->
getName().c_str(), error_msg.c_str());
1439 valid_solver =
false;
1446 if (poses_in.size() > 1)
1449 return setFromIKSubgroups(jmg, poses_in, tips_in, consistency_limit_sets, attempts, timeout, constraint, options);
1459 std::vector<double> consistency_limits;
1460 if (consistency_limit_sets.size() > 1)
1462 ROS_ERROR_NAMED(LOGNAME,
"Invalid number (%zu) of sets of consistency limits for a setFromIK request " 1463 "that is being solved by a single IK solver",
1464 consistency_limit_sets.size());
1467 else if (consistency_limit_sets.size() == 1)
1468 consistency_limits = consistency_limit_sets[0];
1470 const std::vector<std::string>& solver_tip_frames = solver->getTipFrames();
1473 std::vector<bool> tip_frames_used(solver_tip_frames.size(),
false);
1476 std::vector<geometry_msgs::Pose> ik_queries(solver_tip_frames.size());
1479 for (std::size_t i = 0; i < poses_in.size(); ++i)
1482 Eigen::Affine3d pose = poses_in[i];
1483 std::string pose_frame = tips_in[i];
1486 if (!pose_frame.empty() && pose_frame[0] ==
'/')
1487 pose_frame = pose_frame.substr(1);
1495 bool found_valid_frame =
false;
1496 std::size_t solver_tip_id;
1497 for (solver_tip_id = 0; solver_tip_id < solver_tip_frames.size(); ++solver_tip_id)
1500 if (tip_frames_used[solver_tip_id])
1504 std::string solver_tip_frame = solver_tip_frames[solver_tip_id];
1508 if (!solver_tip_frame.empty() && solver_tip_frame[0] ==
'/')
1509 solver_tip_frame = solver_tip_frame.substr(1);
1511 if (pose_frame != solver_tip_frame)
1517 if (ab_trans.size() != 1)
1520 "with multiple geometries as a reference frame.");
1524 pose = pose * ab_trans[0].inverse(Eigen::Isometry);
1526 if (pose_frame != solver_tip_frame)
1535 for (robot_model::LinkTransformMap::const_iterator it = fixed_links.begin(); it != fixed_links.end(); ++it)
1538 pose_frame = solver_tip_frame;
1539 pose = pose * it->second;
1547 if (pose_frame == solver_tip_frame)
1549 found_valid_frame =
true;
1556 if (!found_valid_frame)
1558 ROS_ERROR_NAMED(LOGNAME,
"Cannot compute IK for query %zu pose reference frame '%s'", i, pose_frame.c_str());
1560 std::stringstream ss;
1561 for (solver_tip_id = 0; solver_tip_id < solver_tip_frames.size(); ++solver_tip_id)
1562 ss << solver_tip_frames[solver_tip_id] <<
", ";
1563 ROS_ERROR_NAMED(LOGNAME,
"Available tip frames: [%s]", ss.str().c_str());
1568 tip_frames_used[solver_tip_id] =
true;
1571 geometry_msgs::Pose ik_query;
1575 ik_queries[solver_tip_id] = ik_query;
1579 for (std::size_t solver_tip_id = 0; solver_tip_id < solver_tip_frames.size(); ++solver_tip_id)
1582 if (tip_frames_used[solver_tip_id])
1586 std::string solver_tip_frame = solver_tip_frames[solver_tip_id];
1590 if (!solver_tip_frame.empty() && solver_tip_frame[0] ==
'/')
1591 solver_tip_frame = solver_tip_frame.substr(1);
1601 geometry_msgs::Pose ik_query;
1605 ik_queries[solver_tip_id] = ik_query;
1608 tip_frames_used[solver_tip_id] =
true;
1612 if (timeout < std::numeric_limits<double>::epsilon())
1621 ik_callback_fn = boost::bind(&ikCallbackFnAdapter,
this, jmg, constraint, _1, _2, _3);
1626 bool first_seed =
true;
1627 std::vector<double> initial_values;
1628 for (
unsigned int st = 0; st < attempts; ++st)
1630 std::vector<double> seed(bij.size());
1637 for (std::size_t i = 0; i < bij.size(); ++i)
1638 seed[i] = initial_values[bij[i]];
1642 ROS_DEBUG_NAMED(LOGNAME,
"Rerunning IK solver with random joint positions");
1646 std::vector<double> random_values;
1648 for (std::size_t i = 0; i < bij.size(); ++i)
1649 seed[i] = random_values[bij[i]];
1653 std::vector<unsigned int> red_joints;
1654 solver->getRedundantJoints(red_joints);
1656 for (std::size_t i = 0; i < red_joints.size(); ++i)
1657 seed[red_joints[i]] = initial_values[bij[red_joints[i]]];
1662 std::vector<double> ik_sol;
1663 moveit_msgs::MoveItErrorCodes error;
1665 if (solver->searchPositionIK(ik_queries, seed, timeout, consistency_limits, ik_sol, ik_callback_fn, error, options,
1668 std::vector<double> solution(bij.size());
1669 for (std::size_t i = 0; i < bij.size(); ++i)
1670 solution[bij[i]] = ik_sol[i];
1679 const std::vector<std::string>& tips_in,
1680 const std::vector<std::vector<double> >& consistency_limits,
unsigned int attempts,
1687 std::vector<const JointModelGroup*> sub_groups;
1691 if (poses_in.size() != sub_groups.size())
1693 ROS_ERROR_NAMED(LOGNAME,
"Number of poses (%zu) must be the same as number of sub-groups (%zu)", poses_in.size(),
1698 if (tips_in.size() != sub_groups.size())
1700 ROS_ERROR_NAMED(LOGNAME,
"Number of tip names (%zu) must be same as number of sub-groups (%zu)", tips_in.size(),
1705 if (!consistency_limits.empty() && consistency_limits.size() != sub_groups.size())
1707 ROS_ERROR_NAMED(LOGNAME,
"Number of consistency limit vectors must be the same as number of sub-groups");
1711 for (std::size_t i = 0; i < consistency_limits.size(); ++i)
1713 if (consistency_limits[i].size() != sub_groups[i]->getVariableCount())
1715 ROS_ERROR_NAMED(LOGNAME,
"Number of joints in consistency_limits is %zu but it should be should be %u", i,
1722 std::vector<kinematics::KinematicsBaseConstPtr> solvers;
1723 for (std::size_t i = 0; i < poses_in.size(); ++i)
1725 kinematics::KinematicsBaseConstPtr solver = sub_groups[i]->getSolverInstance();
1731 solvers.push_back(solver);
1736 std::vector<std::string> pose_frames = tips_in;
1739 for (std::size_t i = 0; i < poses_in.size(); ++i)
1741 Eigen::Affine3d& pose = transformed_poses[i];
1742 std::string& pose_frame = pose_frames[i];
1749 std::string solver_tip_frame = solvers[i]->getTipFrame();
1753 if (!solver_tip_frame.empty() && solver_tip_frame[0] ==
'/')
1754 solver_tip_frame = solver_tip_frame.substr(1);
1756 if (pose_frame != solver_tip_frame)
1762 if (ab_trans.size() != 1)
1764 ROS_ERROR_NAMED(LOGNAME,
"Cannot use an attached body with multiple geometries as a reference frame.");
1768 pose = pose * ab_trans[0].inverse(Eigen::Isometry);
1770 if (pose_frame != solver_tip_frame)
1776 for (robot_model::LinkTransformMap::const_iterator it = fixed_links.begin(); it != fixed_links.end(); ++it)
1777 if (it->first->getName() == solver_tip_frame)
1779 pose_frame = solver_tip_frame;
1780 pose = pose * it->second;
1786 if (pose_frame != solver_tip_frame)
1788 ROS_ERROR_NAMED(LOGNAME,
"Cannot compute IK for query pose reference frame '%s', desired: '%s'",
1789 pose_frame.c_str(), solver_tip_frame.c_str());
1795 std::vector<geometry_msgs::Pose> ik_queries(poses_in.size());
1798 ik_callback_fn = boost::bind(&ikCallbackFnAdapter,
this, jmg, constraint, _1, _2, _3);
1800 for (std::size_t i = 0; i < transformed_poses.size(); ++i)
1802 Eigen::Quaterniond quat(transformed_poses[i].linear());
1803 Eigen::Vector3d point(transformed_poses[i].translation());
1804 ik_queries[i].position.x = point.x();
1805 ik_queries[i].position.y = point.y();
1806 ik_queries[i].position.z = point.z();
1807 ik_queries[i].orientation.x = quat.x();
1808 ik_queries[i].orientation.y = quat.y();
1809 ik_queries[i].orientation.z = quat.z();
1810 ik_queries[i].orientation.w = quat.w();
1817 if (timeout < std::numeric_limits<double>::epsilon())
1820 bool first_seed =
true;
1821 for (
unsigned int st = 0; st < attempts; ++st)
1823 bool found_solution =
true;
1824 for (std::size_t sg = 0; sg < sub_groups.size(); ++sg)
1826 const std::vector<unsigned int>& bij = sub_groups[sg]->getKinematicsSolverJointBijection();
1827 std::vector<double> seed(bij.size());
1831 std::vector<double> initial_values;
1833 for (std::size_t i = 0; i < bij.size(); ++i)
1834 seed[i] = initial_values[bij[i]];
1840 std::vector<double> random_values;
1841 sub_groups[sg]->getVariableRandomPositions(rng, random_values);
1842 for (std::size_t i = 0; i < bij.size(); ++i)
1843 seed[i] = random_values[bij[i]];
1847 std::vector<double> ik_sol;
1848 moveit_msgs::MoveItErrorCodes error;
1849 const std::vector<double>& climits = consistency_limits.empty() ? std::vector<double>() : consistency_limits[sg];
1850 if (solvers[sg]->searchPositionIK(ik_queries[sg], seed, timeout, climits, ik_sol, error))
1852 std::vector<double> solution(bij.size());
1853 for (std::size_t i = 0; i < bij.size(); ++i)
1854 solution[bij[i]] = ik_sol[i];
1859 found_solution =
false;
1866 std::vector<double> full_solution;
1868 if (constraint ? constraint(
this, jmg, &full_solution[0]) :
true)
1879 const LinkModel* link,
const Eigen::Vector3d& direction,
1889 const Eigen::Vector3d rotated_direction = global_reference_frame ? direction : start_pose.linear() * direction;
1892 Eigen::Affine3d target_pose = start_pose;
1893 target_pose.translation() += rotated_direction *
distance;
1897 computeCartesianPath(group, traj, link, target_pose,
true, max_step, jump_threshold, validCallback, options));
1901 const LinkModel* link,
const Eigen::Affine3d& target,
1902 bool global_reference_frame,
const MaxEEFStep& max_step,
1909 for (std::size_t i = 0; i < cjnt.size(); ++i)
1916 Eigen::Affine3d rotated_target = global_reference_frame ? target : start_pose * target;
1918 Eigen::Quaterniond start_quaternion(start_pose.linear());
1919 Eigen::Quaterniond target_quaternion(rotated_target.linear());
1924 "Invalid MaxEEFStep passed into computeCartesianPath. Both the MaxEEFStep.rotation and " 1925 "MaxEEFStep.translation components must be non-negative and at least one component must be " 1926 "greater than zero");
1930 double rotation_distance = start_quaternion.angularDistance(target_quaternion);
1931 double translation_distance = (rotated_target.translation() - start_pose.translation()).norm();
1934 std::size_t translation_steps = 0;
1936 translation_steps = floor(translation_distance / max_step.
translation);
1938 std::size_t rotation_steps = 0;
1940 rotation_steps = floor(rotation_distance / max_step.
rotation);
1943 std::size_t steps = std::max(translation_steps, rotation_steps) + 1;
1944 if (jump_threshold.
factor > 0 && steps < MIN_STEPS_FOR_JUMP_THRESH)
1948 traj.push_back(RobotStatePtr(
new RobotState(*
this)));
1950 double last_valid_percentage = 0.0;
1951 for (std::size_t i = 1; i <= steps; ++i)
1953 double percentage = (double)i / (
double)steps;
1955 Eigen::Affine3d pose(start_quaternion.slerp(percentage, target_quaternion));
1956 pose.translation() = percentage * rotated_target.translation() + (1 - percentage) * start_pose.translation();
1960 if (
setFromIK(group, pose, link->
getName(), 1, 0.0, validCallback, options))
1961 traj.push_back(RobotStatePtr(
new RobotState(*
this)));
1965 last_valid_percentage = percentage;
1970 return last_valid_percentage;
1975 bool global_reference_frame,
const MaxEEFStep& max_step,
1980 double percentage_solved = 0.0;
1981 for (std::size_t i = 0; i < waypoints.size(); ++i)
1985 std::vector<RobotStatePtr> waypoint_traj;
1986 double wp_percentage_solved =
computeCartesianPath(group, waypoint_traj, link, waypoints[i], global_reference_frame,
1987 max_step, no_joint_space_jump_test, validCallback, options);
1988 if (fabs(wp_percentage_solved - 1.0) < std::numeric_limits<double>::epsilon())
1990 percentage_solved = (double)(i + 1) / (double)waypoints.size();
1991 std::vector<RobotStatePtr>::iterator
start = waypoint_traj.begin();
1992 if (i > 0 && !waypoint_traj.empty())
1993 std::advance(start, 1);
1994 traj.insert(traj.end(), start, waypoint_traj.end());
1998 percentage_solved += wp_percentage_solved / (double)waypoints.size();
1999 std::vector<RobotStatePtr>::iterator
start = waypoint_traj.begin();
2000 if (i > 0 && !waypoint_traj.empty())
2001 std::advance(start, 1);
2002 traj.insert(traj.end(), start, waypoint_traj.end());
2009 return percentage_solved;
2015 double percentage_solved = 1.0;
2016 if (traj.size() <= 1)
2017 return percentage_solved;
2019 if (jump_threshold.
factor > 0.0)
2025 return percentage_solved;
2029 double jump_threshold_factor)
2033 ROS_WARN_NAMED(LOGNAME,
"The computed trajectory is too short to detect jumps in joint-space " 2034 "Need at least %zu steps, only got %zu. Try a lower max_step.",
2035 MIN_STEPS_FOR_JUMP_THRESH, traj.size());
2038 std::vector<double> dist_vector;
2039 dist_vector.reserve(traj.size() - 1);
2040 double total_dist = 0.0;
2041 for (std::size_t i = 1; i < traj.size(); ++i)
2043 double dist_prev_point = traj[i]->distance(*traj[i - 1], group);
2044 dist_vector.push_back(dist_prev_point);
2045 total_dist += dist_prev_point;
2048 double percentage = 1.0;
2050 double thres = jump_threshold_factor * (total_dist / (double)dist_vector.size());
2051 for (std::size_t i = 0; i < dist_vector.size(); ++i)
2052 if (dist_vector[i] > thres)
2054 ROS_DEBUG_NAMED(LOGNAME,
"Truncating Cartesian path due to detected jump in joint-space distance");
2055 percentage = (double)(i + 1) / (double)(traj.size());
2064 double revolute_threshold,
double prismatic_threshold)
2071 LimitData data[2] = { { revolute_threshold, revolute_threshold > 0.0 },
2072 { prismatic_threshold, prismatic_threshold > 0.0 } };
2073 bool still_valid =
true;
2075 for (std::size_t traj_ix = 0, ix_end = traj.size() - 1; traj_ix != ix_end; ++traj_ix)
2077 for (
auto& joint : joints)
2079 unsigned int type_index;
2080 switch (joint->getType())
2090 "testAbsoluteJointSpaceJump only supports prismatic and revolute joints.",
2091 joint->getName().c_str(), joint->getTypeName().c_str());
2094 if (!data[type_index].
check)
2097 double distance = traj[traj_ix]->distance(*traj[traj_ix + 1], joint);
2098 if (distance > data[type_index].limit)
2100 ROS_DEBUG_NAMED(LOGNAME,
"Truncating Cartesian path due to detected jump of %.4f > %.4f in joint %s", distance,
2101 data[type_index].limit, joint->getName().c_str());
2102 still_valid =
false;
2109 double percent_valid = (double)(traj_ix + 1) / (double)(traj.size());
2110 traj.resize(traj_ix + 1);
2111 return percent_valid;
2122 std::vector<const LinkModel*> links =
robot_model_->getLinkModelsWithCollisionGeometry();
2123 for (std::size_t i = 0; i < links.size(); ++i)
2126 const Eigen::Vector3d& extents = links[i]->getShapeExtentsAtOrigin();
2127 transform.translate(links[i]->getCenteredBoundingBoxOffset());
2130 for (std::map<std::string, AttachedBody*>::const_iterator it =
attached_body_map_.begin();
2134 const std::vector<shapes::ShapeConstPtr>&
shapes = it->second->getShapes();
2135 for (std::size_t i = 0; i < transforms.size(); ++i)
2143 aabb.resize(6, 0.0);
2144 if (!bounding_box.isEmpty())
2148 Eigen::Map<Eigen::VectorXd, Eigen::Unaligned, Eigen::InnerStride<2> >(aabb.data(), 3) = bounding_box.min();
2149 Eigen::Map<Eigen::VectorXd, Eigen::Unaligned, Eigen::InnerStride<2> >(aabb.data() + 1, 3) = bounding_box.max();
2155 const std::vector<std::string>& nm =
robot_model_->getVariableNames();
2156 for (std::size_t i = 0; i < nm.size(); ++i)
2157 out << nm[i] <<
"=" <<
position_[i] << std::endl;
2162 out <<
" * Dirty Joint Transforms: " << std::endl;
2163 const std::vector<const JointModel*>& jm =
robot_model_->getJointModels();
2164 for (std::size_t i = 0; i < jm.size(); ++i)
2166 out <<
" " << jm[i]->
getName() << std::endl;
2169 out <<
" * Dirty Collision Body Transforms: " 2175 out <<
"Robot State @" <<
this << std::endl;
2180 out <<
" * Position: ";
2181 for (std::size_t i = 0; i < n; ++i)
2186 out <<
" * Position: NULL" << std::endl;
2190 out <<
" * Velocity: ";
2191 for (std::size_t i = 0; i < n; ++i)
2196 out <<
" * Velocity: NULL" << std::endl;
2200 out <<
" * Acceleration: ";
2201 for (std::size_t i = 0; i < n; ++i)
2206 out <<
" * Acceleration: NULL" << std::endl;
2210 out <<
" * Dirty Collision Body Transforms: " 2218 Eigen::Quaterniond q(transform.linear());
2219 out <<
"T.xyz = [" << transform.translation().x() <<
", " << transform.translation().y() <<
", " 2220 << transform.translation().z() <<
"], Q.xyzw = [" << q.x() <<
", " << q.y() <<
", " << q.z() <<
", " << q.w()
2221 <<
"]" << std::endl;
2228 out <<
"No transforms computed" << std::endl;
2232 out <<
"Joint transforms:" << std::endl;
2233 const std::vector<const JointModel*>& jm =
robot_model_->getJointModels();
2234 for (std::size_t i = 0; i < jm.size(); ++i)
2236 out <<
" " << jm[i]->getName();
2237 const int idx = jm[i]->getJointIndex();
2244 out <<
"Link poses:" << std::endl;
2245 const std::vector<const LinkModel*>& lm =
robot_model_->getLinkModels();
2246 for (std::size_t i = 0; i < lm.size(); ++i)
2248 out <<
" " << lm[i]->getName() <<
": ";
2255 std::stringstream ss;
2256 ss <<
"ROBOT: " <<
robot_model_->getName() << std::endl;
2263 void getPoseString(std::ostream& ss,
const Eigen::Affine3d& pose,
const std::string& pfx)
2266 for (
int y = 0;
y < 4; ++
y)
2269 for (
int x = 0;
x < 4; ++
x)
2271 ss << std::setw(8) << pose(
y,
x) <<
" ";
2281 std::string pfx = pfx0 +
"+--";
2283 ss << pfx <<
"Joint: " << jm->
getName() << std::endl;
2285 pfx = pfx0 + (last ?
" " :
"| ");
2295 ss << pfx <<
"Link: " << lm->
getName() << std::endl;
2303 for (std::vector<const JointModel*>::const_iterator it = lm->
getChildJointModels().begin();
const std::string & getAttachedLinkName() const
Get the name of the link this body is attached to.
const std::string & getName() const
The name of this link.
void getAttachedBodies(std::vector< const AttachedBody * > &attached_bodies) const
Get all bodies attached to the model corresponding to this state.
random_numbers::RandomNumberGenerator & getRandomNumberGenerator()
Return the instance of a random number generator.
const std::string & getName() const
Get the name of the joint.
A set of options for the kinematics solver.
std::size_t getVariableCount() const
Get the number of variables that describe this joint.
bool hasJointModel(const std::string &joint) const
Check if a joint is part of this group.
void updateMimicJoint(const JointModel *joint)
const kinematics::KinematicsBaseConstPtr & getSolverInstance() const
Core components of MoveIt!
const std::string & getVisualMeshFilename() const
Get the filename of the mesh resource used for visual display of this link.
Eigen::Affine3d * global_collision_body_transforms_
void setJointGroupAccelerations(const std::string &joint_group_name, const double *gstate)
Given accelerations for the variables that make up a group, in the order found in the group (includin...
bool isChain() const
Check if this group is a linear chain.
void computeVariableVelocity(const JointModelGroup *jmg, Eigen::VectorXd &qdot, const Eigen::VectorXd &twist, const LinkModel *tip) const
Given a twist for a particular link (tip), compute the corresponding velocity for every variable and ...
int getVariableGroupIndex(const std::string &variable) const
Get the index of a variable within the group. Return -1 on error.
void printTransforms(std::ostream &out=std::cout) const
double distance(const RobotState &other) const
void printStatePositions(std::ostream &out=std::cout) const
#define ROS_ERROR_STREAM_NAMED(name, args)
std::vector< Eigen::Affine3d, Eigen::aligned_allocator< Eigen::Affine3d > > vector_Affine3d
void setJointEfforts(const JointModel *joint, const double *effort)
#define ROS_WARN_NAMED(name,...)
void updateMimicJoints(const JointModelGroup *group)
Update all mimic joints within group.
double getDefaultIKTimeout() const
Get the default IK timeout.
bool knowsFrameTransform(const std::string &id) const
Check if a transformation matrix from the model frame to frame id is known.
const std::vector< const JointModel * > & getChildJointModels() const
A link may have 0 or more child joints. From those joints there will certainly be other descendant li...
const Eigen::Affine3d & getGlobalLinkTransform(const std::string &link_name)
void poseEigenToMsg(const Eigen::Affine3d &e, geometry_msgs::Pose &m)
const std::string & getName() const
Get the name of the attached body.
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
void copyJointGroupAccelerations(const std::string &joint_group_name, std::vector< double > &gstate) const
For a given group, copy the acceleration values of the variables that make up the group into another ...
bool getVariableDefaultPositions(const std::string &name, std::map< std::string, double > &values) const
Get the values that correspond to a named state as read from the URDF. Return false on failure...
void setVariableVelocities(const double *velocity)
Given an array with velocity values for all variables, set those values as the velocities in this sta...
void attachBody(AttachedBody *attached_body)
Add an attached body to this state. Ownership of the memory for the attached body is assumed by the s...
const std::string & getName() const
Get the name of the joint group.
const JointModel * dirty_collision_body_transforms_
bool checkCollisionTransforms() const
This function is only called in debug mode.
void clearAttachedBodies()
Clear all attached bodies. This calls delete on the AttachedBody instances, if needed.
const Eigen::Affine3d & getFrameTransform(const std::string &id)
Get the transformation matrix from the model frame to the frame identified by id. ...
std::string getName(void *handle)
void updateLinkTransformsInternal(const JointModel *start)
bool checkLinkTransforms() const
This function is only called in debug mode.
Eigen::Affine3d * global_link_transforms_
void setJointGroupVelocities(const std::string &joint_group_name, const double *gstate)
Given velocities for the variables that make up a group, in the order found in the group (including v...
static const int NO_IK_SOLUTION
double * getVariablePositions()
Get a raw pointer to the positions of the variables stored in this state. Use carefully. If you change these values externally you need to make sure you trigger a forced update for the state by calling update(true).
void interpolate(const RobotState &to, double t, RobotState &state) const
Interpolate from this state towards state to, at time t in [0,1]. The result is stored in state...
void setVariablePositions(const double *position)
It is assumed positions is an array containing the new positions for all variables in this state...
std::map< const LinkModel *, Eigen::Affine3d, std::less< const LinkModel * >, Eigen::aligned_allocator< std::pair< const LinkModel *const, Eigen::Affine3d > > > LinkTransformMap
Map from link model instances to Eigen transforms.
void getMissingKeys(const std::map< std::string, double > &variable_map, std::vector< std::string > &missing_variables) const
bool setToIKSolverFrame(Eigen::Affine3d &pose, const kinematics::KinematicsBaseConstPtr &solver)
Convert the frame of reference of the pose to that same frame as the IK solver expects.
void markDirtyJointTransforms(const JointModel *joint)
static double testAbsoluteJointSpaceJump(const JointModelGroup *group, std::vector< RobotStatePtr > &traj, double revolute_jump_threshold, double prismatic_jump_threshold)
Tests for absolute joint space jumps of the trajectory traj.
void copyJointGroupPositions(const std::string &joint_group_name, std::vector< double > &gstate) const
For a given group, copy the position values of the variables that make up the group into another loca...
int getFirstCollisionBodyTransformIndex() const
void setAttachedBodyUpdateCallback(const AttachedBodyCallback &callback)
bool lock_redundant_joints
const AttachedBody * getAttachedBody(const std::string &name) const
Get the attached body named name. Return NULL if not found.
const JointModel * getParentJointModel() const
Get the joint model whose child this link is. There will always be a parent joint.
unsigned int getVariableCount() const
Get the number of variables that describe this joint group. This includes variables necessary for mim...
bool isLinkUpdated(const std::string &name) const
True if this name is in the set of links that are to be updated when the state of this group changes...
void setToDefaultValues()
Set all joints to their default positions. The default position is 0, or if that is not within bounds...
const std::vector< const JointModel * > & getContinuousJointModels() const
Get the array of continuous joints used in this group (may include mimic joints). ...
const std::vector< unsigned int > & getKinematicsSolverJointBijection() const
Return the mapping between the order of the joints in this group and the order of the joints in the k...
void copyFrom(const RobotState &other)
int getLinkIndex() const
The index of this joint when traversing the kinematic tree in depth first fashion.
bool hasAttachedBody(const std::string &id) const
Check if an attached body named id exists in this state.
#define ROS_DEBUG_NAMED(name,...)
const Eigen::Affine3d & getVisualMeshOrigin() const
Get the transform for the visual mesh origin.
void computeAABB(std::vector< double > &aabb) const
Compute an axis-aligned bounding box that contains the current state. The format for aabb is (minx...
int getJointIndex() const
Get the index of this joint within the robot model.
Struct for containing jump_threshold.
bool getJacobian(const JointModelGroup *group, const LinkModel *link, const Eigen::Vector3d &reference_point_position, Eigen::MatrixXd &jacobian, bool use_quaternion_representation=false) const
Compute the Jacobian with reference to a particular point on a given link, for a specified group...
const EigenSTL::vector_Affine3d & getFixedTransforms() const
Get the fixed transform (the transforms to the shapes associated with this body)
virtual double distance(const double *value1, const double *value2) const =0
Compute the distance between two joint states of the same model (represented by the variable values) ...
void update(bool force=false)
Update all transforms.
boost::function< void(AttachedBody *body, bool attached)> AttachedBodyCallback
double computeCartesianPath(const JointModelGroup *group, std::vector< RobotStatePtr > &traj, const LinkModel *link, const Eigen::Vector3d &direction, bool global_reference_frame, double distance, const MaxEEFStep &max_step, const JumpThreshold &jump_threshold, const GroupStateValidityCallbackFn &validCallback=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions())
Compute the sequence of joint values that correspond to a straight Cartesian path for a particular gr...
void getStateTreeJointString(std::ostream &ss, const JointModel *jm, const std::string &pfx0, bool last) const
void getVariableRandomPositions(random_numbers::RandomNumberGenerator &rng, double *values) const
Compute random values for the state of the joint group.
static double testJointSpaceJump(const JointModelGroup *group, std::vector< RobotStatePtr > &traj, const JumpThreshold &jump_threshold)
Tests joint space jumps of a trajectory.
void setToRandomPositionsNearBy(const JointModelGroup *group, const RobotState &near, double distance)
Set all joints in group to random values near the value in . distance is the maximum amount each join...
unsigned char * dirty_joint_transforms_
bool dirtyLinkTransforms() const
This may be thrown if unrecoverable errors occur.
void updateStateWithLinkAt(const std::string &link_name, const Eigen::Affine3d &transform, bool backward=false)
Update the state after setting a particular link to the input global transform pose.
std::pair< double, const JointModel * > getMinDistanceToPositionBounds() const
Get the minimm distance from this state to the bounds. The minimum distance and the joint for which t...
AttachedBodyCallback attached_body_update_callback_
This event is called when there is a change in the attached bodies for this state; The event specifie...
const LinkModel * getAttachedLink() const
Get the model of the link this body is attached to.
const std::vector< shapes::ShapeConstPtr > & getShapes() const
Get shape associated to the collision geometry for this link.
std::string getStateTreeString(const std::string &prefix="") const
Struct for containing max_step for computeCartesianPath.
void computeTransform(const Eigen::Affine3d &parent_link_global_transform)
Recompute global_collision_body_transform given the transform of the parent link. ...
bool integrateVariableVelocity(const JointModelGroup *jmg, const Eigen::VectorXd &qdot, double dt, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn())
Given the velocities for the variables in this group (qdot) and an amount of time (dt)...
RobotState & operator=(const RobotState &other)
Copy operator.
bool satisfiesBounds(double margin=0.0) const
static double testRelativeJointSpaceJump(const JointModelGroup *group, std::vector< RobotStatePtr > &traj, double jump_threshold_factor)
Tests for relative joint space jumps of the trajectory traj.
void extendWithTransformedBox(const Eigen::Affine3d &transform, const Eigen::Vector3d &box)
Extend with a box transformed by the given transform.
bool constructMarkerFromShape(const Shape *shape, visualization_msgs::Marker &mk, bool use_mesh_triangle_list=false)
static const std::size_t MIN_STEPS_FOR_JUMP_THRESH
It is recommended that there are at least 10 steps per trajectory for testing jump thresholds with co...
void printStateInfo(std::ostream &out=std::cout) const
boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, moveit_msgs::MoveItErrorCodes &error_code)> IKCallbackFn
The signature for a callback that can compute IK.
bool setFromIKSubgroups(const JointModelGroup *group, const EigenSTL::vector_Affine3d &poses, const std::vector< std::string > &tips, const std::vector< std::vector< double > > &consistency_limits, unsigned int attempts=0, double timeout=0.0, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions())
setFromIK for multiple poses and tips (end effectors) when no solver exists for the jmg that can solv...
A joint from the robot. Models the transform that this joint applies in the kinematic chain...
const std::vector< const JointModel * > & getJointModels() const
Get all the joints in this group (including fixed and mimic joints).
bool hasLinkModel(const std::string &link) const
Check if a link is part of this group.
const std::vector< std::string > & getVariableNames() const
Get the names of the variables that make up this joint, in the order they appear in corresponding sta...
RobotState(const RobotModelConstPtr &robot_model)
A state can be constructed from a specified robot model. No values are initialized. Call setToDefaultValues() if a state needs to provide valid information.
const std::string LOGNAME
void getRobotMarkers(visualization_msgs::MarkerArray &arr, const std::vector< std::string > &link_names, const std_msgs::ColorRGBA &color, const std::string &ns, const ros::Duration &dur, bool include_attached=false) const
Get a MarkerArray that fully describes the robot markers for a given robot.
ROSCPP_DECL bool del(const std::string &key)
unsigned int getDefaultIKAttempts() const
Get the default IK attempts.
const std::vector< int > & getVariableIndexList() const
Get the index locations in the complete robot state for all the variables in this group...
void copyJointGroupVelocities(const std::string &joint_group_name, std::vector< double > &gstate) const
For a given group, copy the velocity values of the variables that make up the group into another loca...
bool setFromDiffIK(const JointModelGroup *group, const Eigen::VectorXd &twist, const std::string &tip, double dt, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn())
Set the joint values from a Cartesian velocity applied during a time dt.
virtual void computeTransform(const double *joint_values, Eigen::Affine3d &transf) const =0
Given the joint values for a joint, compute the corresponding transform.
const JointModel * dirty_link_transforms_
int getFirstVariableIndex() const
Get the index of this joint's first variable within the full robot state.
const Eigen::Vector3d & getVisualMeshScale() const
Get the scale of the mesh resource for this link.
const LinkModel * getChildLinkModel() const
Get the link that this joint connects to. There will always be such a link.
const LinkModel * getLinkModel(const std::string &link) const
Get the model of a particular link.
void setJointGroupPositions(const std::string &joint_group_name, const double *gstate)
Given positions for the variables that make up a group, in the order found in the group (including va...
random_numbers::RandomNumberGenerator * rng_
For certain operations a state needs a random number generator. However, it may be slightly expensive...
void setToRandomPositions()
Set all joints to random values. Values will be within default bounds.
RobotModelConstPtr robot_model_
void setVariableAccelerations(const double *acceleration)
Given an array with acceleration values for all variables, set those values as the accelerations in t...
#define ROS_ERROR_NAMED(name,...)
const LinkTransformMap & getAssociatedFixedTransforms() const
Get the set of links that are attached to this one via fixed transforms.
void updateCollisionBodyTransforms()
Update the transforms for the collision bodies. This call is needed before calling collision checking...
const LinkModel * getParentLinkModel() const
Get the link that this joint connects to. The robot is assumed to start with a joint, so the root joint will return a NULL pointer here.
const Eigen::Affine3d & getJointTransform(const std::string &joint_name)
Representation of a robot's state. This includes position, velocity, acceleration and effort...
const std::vector< const JointModel * > & getActiveJointModels() const
Get the active joints in this group (that have controllable DOF). This does not include mimic joints...
void updateLinkTransforms()
Update the reference frame transforms for links. This call is needed before using the transforms of l...
const std::vector< const LinkModel * > & getLinkModels() const
Get the links that are part of this joint group.
A link from the robot. Contains the constant transform applied to the link and its geometry...
const Eigen::Affine3d & getJointOriginTransform() const
When transforms are computed for this link, they are usually applied to the link's origin...
void setVariableEffort(const double *effort)
Given an array with effort values for all variables, set those values as the effort in this state...
const LinkModel * getParentLinkModel() const
Get the link model whose child this link is (through some joint). There may not always be a parent li...
const std::vector< const LinkModel * > & getDescendantLinkModels() const
Get all the link models that descend from this joint, in the kinematic tree.
bool dirtyJointTransform(const JointModel *joint) const
const double * getJointPositions(const std::string &joint_name) const
void twistMsgToEigen(const geometry_msgs::Twist &m, Eigen::Matrix< double, 6, 1 > &e)
bool isValidVelocityMove(const RobotState &other, const JointModelGroup *group, double dt) const
Check that the time to move between two waypoints is sufficient given velocity limits and time step...
Main namespace for MoveIt!
bool setFromIK(const JointModelGroup *group, const geometry_msgs::Pose &pose, unsigned int attempts=0, double timeout=0.0, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions())
If the group this state corresponds to is a chain and a solver is available, then the joint values ca...
Eigen::Vector3d computeShapeExtents(const ShapeMsg &shape_msg)
std::size_t getVariableCount() const
Get the number of variables that make up this state.
Object defining bodies that can be attached to robot links. This is useful when handling objects pick...
Eigen::Affine3d * variable_joint_transforms_
std::ostream & operator<<(std::ostream &out, const VariableBounds &b)
Operator overload for printing variable bounds to a stream.
std::vector< VariableBounds > Bounds
The datatype for the joint bounds.
bool isContiguousWithinState() const
JointType getType() const
Get the type of joint.
bool dirtyCollisionBodyTransforms() const
boost::function< bool(RobotState *robot_state, const JointModelGroup *joint_group, const double *joint_group_variable_values)> GroupStateValidityCallbackFn
Signature for functions that can verify that if the group joint_group in robot_state is set to joint_...
void printDirtyInfo(std::ostream &out=std::cout) const
std::map< std::string, AttachedBody * > attached_body_map_
All attached bodies that are part of this state, indexed by their name.
bool checkJointTransforms(const JointModel *joint) const
This function is only called in debug mode.
void printTransform(const Eigen::Affine3d &transform, std::ostream &out=std::cout) const
void getSubgroups(std::vector< const JointModelGroup * > &sub_groups) const
Get the groups that are subsets of this one (in terms of joints set)
bool clearAttachedBody(const std::string &id)
Remove the attached body named id. Return false if the object was not found (and thus not removed)...
void invertVelocity()
Invert velocity if present.
Represents an axis-aligned bounding box.