40 #include <boost/math/constants/constants.hpp> 47 #include "order_robot_model_items.inc" 53 const std::string
LOGNAME =
"robot_model";
95 if (urdf_model.getRoot())
97 const urdf::Link* root_link_ptr = urdf_model.getRoot().get();
111 ROS_WARN_NAMED(LOGNAME,
"No geometry is associated to any robot links");
130 typedef std::map<const JointModel*, std::pair<std::set<const LinkModel*, OrderLinksByIndex>,
131 std::set<const JointModel*, OrderJointsByIndex> > >
134 void computeDescendantsHelper(
const JointModel* joint, std::vector<const JointModel*>& parents,
135 std::set<const JointModel*>& seen, DescMap& descendants)
139 if (seen.find(joint) != seen.end())
143 for (std::size_t i = 0; i < parents.size(); ++i)
144 descendants[parents[i]].second.insert(joint);
150 for (std::size_t i = 0; i < parents.size(); ++i)
151 descendants[parents[i]].first.insert(lm);
152 descendants[joint].first.insert(lm);
154 parents.push_back(joint);
156 for (std::size_t i = 0; i < ch.size(); ++i)
157 computeDescendantsHelper(ch[i], parents, seen, descendants);
159 for (std::size_t i = 0; i < mim.size(); ++i)
160 computeDescendantsHelper(mim[i], parents, seen, descendants);
164 void computeCommonRootsHelper(
const JointModel* joint, std::vector<int>& common_roots,
int size)
173 for (std::size_t i = 0; i < ch.size(); ++i)
175 const std::vector<const JointModel*>& a = ch[i]->getDescendantJointModels();
176 for (std::size_t j = i + 1; j < ch.size(); ++j)
178 const std::vector<const JointModel*>& b = ch[j]->getDescendantJointModels();
179 for (std::size_t m = 0; m < b.size(); ++m)
180 common_roots[ch[i]->getJointIndex() * size + b[m]->getJointIndex()] =
181 common_roots[ch[i]->getJointIndex() + b[m]->getJointIndex() * size] = joint->
getJointIndex();
182 for (std::size_t k = 0; k < a.size(); ++k)
184 common_roots[a[k]->getJointIndex() * size + ch[j]->getJointIndex()] =
185 common_roots[a[k]->getJointIndex() + ch[j]->getJointIndex() * size] = joint->
getJointIndex();
186 for (std::size_t m = 0; m < b.size(); ++m)
187 common_roots[a[k]->getJointIndex() * size + b[m]->getJointIndex()] =
188 common_roots[a[k]->getJointIndex() + b[m]->getJointIndex() * size] = joint->
getJointIndex();
191 computeCommonRootsHelper(ch[i], common_roots, size);
220 for (std::size_t j = 0; j < d.size(); ++j)
232 std::vector<const JointModel*> parents;
233 std::set<const JointModel*> seen;
236 computeDescendantsHelper(
root_joint_, parents, seen, descendants);
237 for (DescMap::iterator it = descendants.begin(); it != descendants.end(); ++it)
240 for (std::set<const JointModel*>::const_iterator jt = it->second.second.begin(); jt != it->second.second.end();
243 for (std::set<const LinkModel*>::const_iterator jt = it->second.first.begin(); jt != it->second.first.end(); ++jt)
265 if (!name_order.empty())
267 for (std::size_t j = 0; j < name_order.size(); ++j)
289 std::size_t vc = joint_model_vector_[i]->getVariableCount();
301 if (link_considered[link->getLinkIndex()])
305 computeFixedTransforms(link, link->getJointOriginTransform().inverse(Eigen::Isometry), associated_transforms);
306 for (
auto& tf_base : associated_transforms)
308 link_considered[tf_base.first->getLinkIndex()] =
true;
309 for (
auto& tf_target : associated_transforms)
311 if (&tf_base != &tf_target)
313 ->addAssociatedFixedTransform(tf_target.first,
314 tf_base.second.inverse(Eigen::Isometry) * tf_target.second);
326 const std::vector<srdf::Model::GroupState>& ds = srdf_model.
getGroupStates();
327 for (std::size_t i = 0; i < ds.size(); ++i)
332 std::map<std::string, double> state;
333 for (std::map<std::string, std::vector<double> >::const_iterator jt = ds[i].joint_values_.begin();
334 jt != ds[i].joint_values_.end(); ++jt)
340 if (vn.size() == jt->second.size())
341 for (std::size_t j = 0; j < vn.size(); ++j)
342 state[vn[j]] = jt->second[j];
344 ROS_ERROR_NAMED(LOGNAME,
"The model for joint '%s' requires %d variable values, " 345 "but only %d variable values were supplied in default state '%s' for group '%s'",
346 jt->first.c_str(), (int)vn.size(), (int)jt->second.size(), ds[i].name_.c_str(),
350 ROS_ERROR_NAMED(LOGNAME,
"Group state '%s' specifies value for joint '%s', " 351 "but that joint is not part of group '%s'",
352 ds[i].name_.c_str(), jt->first.c_str(), jmg->
getName().c_str());
358 ROS_ERROR_NAMED(LOGNAME,
"Group state '%s' specified for group '%s', but that group does not exist",
359 ds[i].name_.c_str(), ds[i].group_.c_str());
372 JointModelMap::const_iterator jit =
joint_model_map_.find(jm->mimic->joint_name);
378 ROS_ERROR_NAMED(LOGNAME,
"Join '%s' cannot mimic joint '%s' because they have different number of DOF",
406 ROS_ERROR_NAMED(LOGNAME,
"Cycle found in joint that mimic each other. Ignoring all mimic joints.");
485 const std::vector<srdf::Model::Group>& group_configs = srdf_model.
getGroups();
488 std::vector<bool> processed(group_configs.size(),
false);
496 for (std::size_t i = 0; i < group_configs.size(); ++i)
500 bool all_subgroups_added =
true;
501 for (std::size_t j = 0; j < group_configs[i].subgroups_.size(); ++j)
504 all_subgroups_added =
false;
507 if (all_subgroups_added)
512 ROS_WARN_NAMED(LOGNAME,
"Failed to add group '%s'", group_configs[i].name_.c_str());
517 for (std::size_t i = 0; i < processed.size(); ++i)
519 ROS_WARN_NAMED(LOGNAME,
"Could not process group '%s' due to unmet subgroup dependencies",
520 group_configs[i].name_.c_str());
541 std::vector<std::string> subgroup_names;
545 if (jt->first != it->first)
549 const std::vector<const JointModel*>& sub_joints = sub_jmg->
getJointModels();
550 for (std::size_t k = 0; k < sub_joints.size(); ++k)
551 if (joints.find(sub_joints[k]) == joints.end())
557 subgroup_names.push_back(sub_jmg->
getName());
559 if (!subgroup_names.empty())
567 const std::vector<srdf::Model::EndEffector>& eefs = srdf_model.
getEndEffectors();
571 for (std::size_t k = 0; k < eefs.size(); ++k)
572 if (eefs[k].component_group_ == it->first)
575 it->second->setEndEffectorName(eefs[k].name_);
581 std::vector<JointModelGroup*> possible_parent_groups;
584 if (jt->first != it->first)
586 if (jt->second->hasLinkModel(eefs[k].parent_link_))
588 jt->second->attachEndEffector(eefs[k].name_);
589 possible_parent_groups.push_back(jt->second);
595 if (!eefs[k].parent_group_.empty())
600 if (jt->second->hasLinkModel(eefs[k].parent_link_))
602 if (jt->second != it->second)
603 eef_parent_group = jt->second;
605 ROS_ERROR_NAMED(LOGNAME,
"Group '%s' for end-effector '%s' cannot be its own parent",
606 eefs[k].parent_group_.c_str(), eefs[k].name_.c_str());
609 ROS_ERROR_NAMED(LOGNAME,
"Group '%s' was specified as parent group for end-effector '%s' " 610 "but it does not include the parent link '%s'",
611 eefs[k].parent_group_.c_str(), eefs[k].name_.c_str(), eefs[k].parent_link_.c_str());
614 ROS_ERROR_NAMED(LOGNAME,
"Group name '%s' not found (specified as parent group for end-effector '%s')",
615 eefs[k].parent_group_.c_str(), eefs[k].name_.c_str());
619 if (eef_parent_group ==
nullptr)
620 if (!possible_parent_groups.empty())
624 std::size_t best = 0;
625 for (std::size_t g = 1; g < possible_parent_groups.size(); ++g)
627 possible_parent_groups[best]->getJointModels().size())
629 eef_parent_group = possible_parent_groups[best];
632 if (eef_parent_group)
638 ROS_WARN_NAMED(LOGNAME,
"Could not identify parent group for end-effector '%s'", eefs[k].name_.c_str());
639 it->second->setEndEffectorParent(
"", eefs[k].parent_link_);
651 ROS_WARN_NAMED(LOGNAME,
"A group named '%s' already exists. Not adding.", gc.
name_.c_str());
655 std::set<const JointModel*> jset;
658 for (std::size_t i = 0; i < gc.
chains_.size(); ++i)
662 if (base_link && tip_link)
666 std::vector<const JointModel*> cj;
680 std::size_t
index = 0;
681 std::vector<const JointModel*> cj2;
684 for (std::size_t j = 0; j < cj.size(); ++j)
697 jset.insert(cj.begin(), cj.begin() + index);
698 jset.insert(cj2.begin(), cj2.end());
703 jset.insert(cj.begin(), cj.end());
708 for (std::size_t i = 0; i < gc.
joints_.size(); ++i)
716 for (std::size_t i = 0; i < gc.
links_.size(); ++i)
724 for (std::size_t i = 0; i < gc.
subgroups_.size(); ++i)
731 for (std::size_t j = 0; j < js.size(); ++j)
736 for (std::size_t j = 0; j < fs.size(); ++j)
741 for (std::size_t j = 0; j < ms.size(); ++j)
748 ROS_WARN_NAMED(LOGNAME,
"Group '%s' must have at least one valid joint", gc.
name_.c_str());
752 std::vector<const JointModel*> joints;
753 for (std::set<const JointModel*>::iterator it = jset.begin(); it != jset.end(); ++it)
754 joints.push_back(*it);
768 if (joint ==
nullptr)
800 for (std::size_t i = 0; i < urdf_link->child_links.size(); ++i)
812 static inline VariableBounds jointBoundsFromURDF(
const urdf::Joint* urdf_joint)
815 if (urdf_joint->safety)
820 if (urdf_joint->limits)
830 if (urdf_joint->limits)
837 if (urdf_joint->limits)
855 switch (urdf_joint->type)
857 case urdf::Joint::REVOLUTE:
862 j->
setAxis(Eigen::Vector3d(urdf_joint->axis.x, urdf_joint->axis.y, urdf_joint->axis.z));
866 case urdf::Joint::CONTINUOUS:
871 j->
setAxis(Eigen::Vector3d(urdf_joint->axis.x, urdf_joint->axis.y, urdf_joint->axis.z));
875 case urdf::Joint::PRISMATIC:
879 j->
setAxis(Eigen::Vector3d(urdf_joint->axis.x, urdf_joint->axis.y, urdf_joint->axis.z));
883 case urdf::Joint::FLOATING:
886 case urdf::Joint::PLANAR:
889 case urdf::Joint::FIXED:
893 ROS_ERROR_NAMED(LOGNAME,
"Unknown joint type: %d", (
int)urdf_joint->type);
899 const std::vector<srdf::Model::VirtualJoint>& vjoints = srdf_model.
getVirtualJoints();
900 for (std::size_t i = 0; i < vjoints.size(); ++i)
902 if (vjoints[i].child_link_ != child_link->name)
904 ROS_WARN_NAMED(LOGNAME,
"Skipping virtual joint '%s' because its child frame '%s' " 905 "does not match the URDF frame '%s'",
906 vjoints[i].name_.c_str(), vjoints[i].child_link_.c_str(), child_link->name.c_str());
908 else if (vjoints[i].parent_frame_.empty())
910 ROS_WARN_NAMED(LOGNAME,
"Skipping virtual joint '%s' because its parent frame is empty",
911 vjoints[i].name_.c_str());
915 if (vjoints[i].type_ ==
"fixed")
917 else if (vjoints[i].type_ ==
"planar")
919 else if (vjoints[i].type_ ==
"floating")
924 if (vjoints[i].type_ !=
"fixed")
936 ROS_INFO_NAMED(LOGNAME,
"No root/virtual joint specified in SRDF. Assuming fixed joint");
944 const std::vector<srdf::Model::PassiveJoint>& pjoints = srdf_model.
getPassiveJoints();
945 for (std::size_t i = 0; i < pjoints.size(); ++i)
947 if (result->
getName() == pjoints[i].name_)
960 static inline Eigen::Affine3d urdfPose2Affine3d(
const urdf::Pose& pose)
962 Eigen::Quaterniond q(pose.rotation.w, pose.rotation.x, pose.rotation.y, pose.rotation.z);
963 Eigen::Affine3d af(Eigen::Translation3d(pose.position.x, pose.position.y, pose.position.z) * q.toRotationMatrix());
972 const std::vector<urdf::CollisionSharedPtr>& col_array =
973 urdf_link->collision_array.empty() ? std::vector<urdf::CollisionSharedPtr>(1, urdf_link->collision) :
974 urdf_link->collision_array;
976 std::vector<shapes::ShapeConstPtr>
shapes;
979 for (std::size_t i = 0; i < col_array.size(); ++i)
980 if (col_array[i] && col_array[i]->geometry)
986 poses.push_back(urdfPose2Affine3d(col_array[i]->origin));
991 const std::vector<urdf::VisualSharedPtr>& vis_array = urdf_link->visual_array.empty() ?
992 std::vector<urdf::VisualSharedPtr>(1, urdf_link->visual) :
993 urdf_link->visual_array;
994 for (std::size_t i = 0; i < vis_array.size(); ++i)
995 if (vis_array[i] && vis_array[i]->geometry)
1001 poses.push_back(urdfPose2Affine3d(vis_array[i]->origin));
1009 if (urdf_link->visual && urdf_link->visual->geometry)
1011 if (urdf_link->visual->geometry->type == urdf::Geometry::MESH)
1013 const urdf::Mesh* mesh =
static_cast<const urdf::Mesh*
>(urdf_link->visual->geometry.get());
1014 if (!mesh->filename.empty())
1015 result->
setVisualMesh(mesh->filename, urdfPose2Affine3d(urdf_link->visual->origin),
1016 Eigen::Vector3d(mesh->scale.x, mesh->scale.y, mesh->scale.z));
1019 else if (urdf_link->collision && urdf_link->collision->geometry)
1021 if (urdf_link->collision->geometry->type == urdf::Geometry::MESH)
1023 const urdf::Mesh* mesh =
static_cast<const urdf::Mesh*
>(urdf_link->collision->geometry.get());
1024 if (!mesh->filename.empty())
1025 result->
setVisualMesh(mesh->filename, urdfPose2Affine3d(urdf_link->collision->origin),
1026 Eigen::Vector3d(mesh->scale.x, mesh->scale.y, mesh->scale.z));
1030 if (urdf_link->parent_joint)
1031 result->
setJointOriginTransform(urdfPose2Affine3d(urdf_link->parent_joint->parent_to_joint_origin_transform));
1043 case urdf::Geometry::SPHERE:
1044 result =
new shapes::Sphere(static_cast<const urdf::Sphere*>(geom)->radius);
1046 case urdf::Geometry::BOX:
1048 urdf::Vector3 dim =
static_cast<const urdf::Box*
>(geom)->dim;
1052 case urdf::Geometry::CYLINDER:
1053 result =
new shapes::Cylinder(static_cast<const urdf::Cylinder*>(geom)->radius,
1054 static_cast<const urdf::Cylinder*>(geom)->length);
1056 case urdf::Geometry::MESH:
1058 const urdf::Mesh* mesh =
static_cast<const urdf::Mesh*
>(geom);
1059 if (!mesh->filename.empty())
1061 Eigen::Vector3d scale(mesh->scale.x, mesh->scale.y, mesh->scale.z);
1068 ROS_ERROR_NAMED(LOGNAME,
"Unknown geometry type: %d", (
int)geom->type);
1159 int src =
mimic_joints_[i]->getMimic()->getFirstVariableIndex();
1173 std::map<std::string, double>& values)
const 1199 std::vector<std::string>& missing_variables)
const 1201 missing_variables.clear();
1202 std::set<std::string> keys(variables.begin(), variables.end());
1219 double max_distance = 0.0;
1223 return max_distance;
1227 double margin)
const 1232 *active_joint_bounds[i], margin))
1240 bool change =
false;
1243 *active_joint_bounds[i]))
1276 std::map<std::string, SolverAllocatorFn>::const_iterator jt = allocators.find(jmg->getName());
1277 if (jt != allocators.end())
1279 std::pair<SolverAllocatorFn, SolverAllocatorMapFn> result;
1280 result.first = jt->second;
1281 jmg->setSolverAllocators(result);
1289 std::pair<SolverAllocatorFn, SolverAllocatorMapFn> result;
1290 std::map<std::string, SolverAllocatorFn>::const_iterator jt = allocators.find(jmg->getName());
1291 if (jt == allocators.end())
1294 std::set<const JointModel*> joints;
1295 joints.insert(jmg->getJointModels().begin(), jmg->getJointModels().end());
1297 std::vector<const JointModelGroup*> subs;
1300 for (std::map<std::string, SolverAllocatorFn>::const_iterator kt = allocators.begin(); kt != allocators.end();
1309 std::set<const JointModel*> sub_joints;
1312 if (std::includes(joints.begin(), joints.end(), sub_joints.begin(), sub_joints.end()))
1314 std::set<const JointModel*> resultj;
1315 std::set_difference(joints.begin(), joints.end(), sub_joints.begin(), sub_joints.end(),
1316 std::inserter(resultj, resultj.end()));
1322 subs.push_back(sub);
1323 joints.swap(resultj);
1330 std::stringstream ss;
1331 for (std::size_t i = 0; i < subs.size(); ++i)
1333 ss << subs[i]->getName() <<
" ";
1334 result.second[subs[i]] = allocators.find(subs[i]->
getName())->second;
1336 ROS_DEBUG_NAMED(LOGNAME,
"Added sub-group IK allocators for group '%s': [ %s]", jmg->getName().c_str(),
1339 jmg->setSolverAllocators(result);
1349 std::ios_base::fmtflags old_flags = out.flags();
1350 out.setf(std::ios::fixed, std::ios::floatfield);
1351 std::streamsize old_prec = out.precision();
1353 out <<
"Joints: " << std::endl;
1360 out <<
" * " << vn.size() << (vn.size() > 1 ?
" variables:" : (vn.empty() ?
" variables" :
" variable:"))
1363 for (std::vector<std::string>::const_iterator it = vn.begin(); it != vn.end(); ++it)
1365 out <<
" * '" << *it <<
"', index " << idx++ <<
" in full state";
1375 out.precision(old_prec);
1376 out.flags(old_flags);
1377 out <<
"Links: " << std::endl;
1381 <<
" geoms" << std::endl;
1384 <<
"parent joint is fixed" << std::endl;
1387 <<
"joint origin transform is identity" << std::endl;
1390 out <<
"Available groups: " << std::endl;
std::vector< const JointModel * > mimic_joints_
The set of mimic joints this model contains.
const std::string & getName() const
The name of this link.
void setChildLinkModel(const LinkModel *link)
void printModelInfo(std::ostream &out) const
Print information about the constructed model.
std::vector< std::string > subgroups_
const std::string & getName() const
Get the name of the joint.
bool hasJointModel(const std::string &joint) const
Check if a joint is part of this group.
void setContinuous(bool flag)
std::vector< LinkModel * > link_model_vector_
The vector of links that are updated when computeTransforms() is called, in the order they are update...
JointModel * constructJointModel(const urdf::Joint *urdf_joint_model, const urdf::Link *child_link, const srdf::Model &srdf_model)
Given a urdf joint model, a child link and a set of virtual joints, build up the corresponding JointM...
std::vector< const JointModel * > joints_of_variable_
The joints that correspond to each variable index.
std::vector< std::string > link_model_names_vector_
The vector of link names that corresponds to link_model_vector_.
void setEndEffectorParent(const std::string &group, const std::string &link)
If this group is an end-effector, specify the parent group (e.g., the arm holding the eef) and the li...
#define ROS_INFO_NAMED(name,...)
const std::string & getName() const
Get the model name.
const JointModel * getJointModel(const std::string &joint) const
Get a joint by its name. Throw an exception if the joint is not part of this group.
std::vector< const LinkModel * > link_model_vector_const_
The vector of links that are updated when computeTransforms() is called, in the order they are update...
std::vector< Eigen::Affine3d, Eigen::aligned_allocator< Eigen::Affine3d > > vector_Affine3d
const std::vector< VirtualJoint > & getVirtualJoints() const
#define ROS_WARN_NAMED(name,...)
JointBoundsVector active_joint_models_bounds_
The bounds for all the active joint models.
static const moveit::core::LinkModel * getRigidlyConnectedParentLinkModel(const LinkModel *link)
Get the latest link upwards the kinematic tree, which is only connected via fixed joints...
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...
LinkModelMap link_model_map_
A map from link names to their instances.
std::vector< std::pair< std::string, std::string > > chains_
void getVariableRandomPositions(random_numbers::RandomNumberGenerator &rng, double *values) const
Compute the random values for a RobotState.
const JointModel * getJointOfVariable(int variable_index) const
const std::vector< const JointModel * > & getMimicRequests() const
The joint models whose values would be modified if the value of this joint changed.
RobotModel(const urdf::ModelInterfaceSharedPtr &urdf_model, const srdf::ModelConstSharedPtr &srdf_model)
Construct a kinematic model from a parsed description and a list of planning groups.
void buildJointInfo()
Compute helpful information about joints.
void setJointIndex(int index)
Set the index of this joint within the robot model.
void addDescendantJointModel(const JointModel *joint)
const std::string & getName() const
Get the name of the joint group.
void setAxis(const Eigen::Vector3d &axis)
Set the axis of translation.
const LinkModel * getLinkModel(const std::string &link) const
Get a link by its name. Output error and return NULL when the link is missing.
const LinkModel * root_link_
The first physical link for the robot.
const VariableBounds & getVariableBounds(const std::string &variable) const
Get the bounds for a specific variable. Throw an exception of variable is not found.
std::size_t getVariableCount() const
Get the number of variables that describe this model.
const std::vector< const JointModel * > & getMimicJointModels() const
Get the mimic joints that are part of this group.
JointModelGroupMap end_effectors_map_
The known end effectors.
void setJointOriginTransform(const Eigen::Affine3d &transform)
~RobotModel()
Destructor. Clear all memory.
const JointModel * getRootJoint() const
Get the root joint. There will be one root joint unless the model is empty. This is either extracted ...
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.
double distance(const double *state1, const double *state2) const
std::shared_ptr< Shape > ShapePtr
__attribute__((deprecated)) std const std::vector< Group > & getGroups() const
const JointModelGroup * getEndEffector(const std::string &name) const
Get the joint group that corresponds to a given end-effector name.
void setFirstCollisionBodyTransformIndex(int index)
Definition of a kinematic model. This class is not thread safe, however multiple instances can be cre...
void buildGroups(const srdf::Model &srdf_model)
Given a SRDF model describing the groups, build up the groups in this kinematic model.
const JointModelGroup * getJointModelGroup(const std::string &name) const
Get a joint group from this model (by name)
void setKinematicsAllocators(const std::map< std::string, SolverAllocatorFn > &allocators)
A map of known kinematics solvers (associated to their group name)
void addDefaultState(const std::string &name, const std::map< std::string, double > &default_state)
void addChildJointModel(const JointModel *joint)
void buildModel(const urdf::ModelInterface &urdf_model, const srdf::Model &srdf_model)
Given an URDF model and a SRDF model, build a full kinematic model.
const JointModel * getParentJointModel() const
Get the joint model whose child this link is. There will always be a parent joint.
const JointModel * getJointModel(const std::string &joint) const
Get a joint by its name. Output error and return NULL when the joint is missing.
std::string model_name_
The name of the model.
LinkModel * constructLinkModel(const urdf::Link *urdf_link)
Given a urdf link, build the corresponding LinkModel object.
#define ROS_DEBUG_NAMED(name,...)
shapes::ShapePtr constructShape(const urdf::Geometry *geom)
Given a geometry spec from the URDF and a filename (for a mesh), construct the corresponding shape ob...
VariableIndexMap joint_variables_index_map_
The state includes all the joint variables that make up the joints the state consists of...
const std::vector< const JointModel * > & getFixedJointModels() const
Get the fixed joints that are part of this group.
void computeDescendants()
For every joint, pre-compute the list of descendant joints & links.
int getJointIndex() const
Get the index of this joint within the robot model.
void setSubgroupNames(const std::vector< std::string > &subgroups)
Set the names of the subgroups for this group.
JointModelGroupMap joint_model_group_map_
A map from group names to joint groups.
void computeFixedTransforms(const LinkModel *link, const Eigen::Affine3d &transform, LinkTransformMap &associated_transforms)
Get the transforms between link and all its rigidly attached descendants.
std::vector< const JointModel::Bounds * > JointBoundsVector
void setAxis(const Eigen::Vector3d &axis)
Set the axis of rotation.
std::size_t variable_count_
Get the number of variables necessary to describe this model.
This may be thrown if unrecoverable errors occur.
const JointModel * root_joint_
The root joint.
std::vector< const JointModel * > joint_model_vector_const_
The vector of joints in the model, in the order they appear in the state vector.
const std::vector< shapes::ShapeConstPtr > & getShapes() const
Get shape associated to the collision geometry for this link.
srdf::ModelConstSharedPtr srdf_
void addDescendantLinkModel(const LinkModel *link)
std::vector< const JointModelGroup * > joint_model_groups_const_
The array of joint model groups, in alphabetical order.
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 enforcePositionBounds(double *state) const
void setLinkIndex(int index)
void buildGroupsInfo_EndEffectors(const srdf::Model &srdf_model)
Compute helpful information about groups (that can be queried later)
std::vector< const JointModel * > continuous_joint_model_vector_
The set of continuous joints this model contains.
void setParentLinkModel(const LinkModel *link)
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...
std::vector< const JointModel * > single_dof_joints_
std::vector< std::string > links_
const std::string LOGNAME
std::vector< const JointModelGroup * > end_effectors_
The array of end-effectors, in alphabetical order.
void updateMimicJoints(double *values) const
Update the variable values for the state of a group with respect to the mimic joints.
void computeCommonRoots()
For every pair of joints, pre-compute the common roots of the joints.
std::vector< JointModel * > active_joint_model_vector_
The vector of joints in the model, in the order they appear in the state vector.
const LinkModel * getRootLink() const
Get the physical root link of the robot.
std::size_t link_geometry_count_
Total number of geometric shapes in this model.
JointModelMap joint_model_map_
A map from joint names to their instances.
Mesh * createMeshFromResource(const std::string &resource)
const std::vector< PassiveJoint > & getPassiveJoints() const
void setGeometry(const std::vector< shapes::ShapeConstPtr > &shapes, const EigenSTL::vector_Affine3d &origins)
const LinkModel * getChildLinkModel() const
Get the link that this joint connects to. There will always be such a link.
std::vector< std::string > joint_model_names_vector_
The vector of joint names that corresponds to joint_model_vector_.
urdf::ModelInterfaceSharedPtr urdf_
bool hasJointModel(const std::string &name) const
Check if a joint exists. Return true if it does.
std::string model_frame_
The reference frame for this model.
void buildGroupsInfo_Subgroups(const srdf::Model &srdf_model)
Compute helpful information about groups (that can be queried later)
std::vector< std::string > joints_
#define ROS_ERROR_NAMED(name,...)
std::vector< JointModel * > joint_model_vector_
The vector of joints in the model, in the order they appear in the state vector.
std::vector< std::string > variable_names_
The names of the DOF that make up this state (this is just a sequence of joint variable names; not ne...
void getMissingVariableNames(const std::vector< std::string > &variables, std::vector< std::string > &missing_variables) const
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.
bool addJointModelGroup(const srdf::Model::Group &group)
Construct a JointModelGroup given a SRDF description group.
void interpolate(const double *from, const double *to, double t, double *state) const
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...
std::vector< int > active_joint_model_start_index_
int getVariableIndex(const std::string &variable) const
Get the index of a variable in the robot state.
bool hasEndEffector(const std::string &eef) const
Check if an end effector exists.
std::vector< const JointModel * > multi_dof_joints_
bool hasLinkModel(const std::string &name) const
Check if a link exists. Return true if it does.
const LinkModel * getParentLinkModel() const
Get the link model whose child this link is (through some joint). There may not always be a parent li...
void buildMimic(const urdf::ModelInterface &urdf_model)
Given the URDF model, build up the mimic joints (mutually constrained joints)
void setParentJointModel(const JointModel *joint)
std::vector< JointModelGroup * > joint_model_groups_
The array of joint model groups, in alphabetical order.
const std::vector< const JointModel * > & getJointModels() const
Get the array of joints, in the order they appear in the robot state.
Main namespace for MoveIt!
std::vector< std::string > joint_model_group_names_
A vector of all group names, in alphabetical order.
void setParentLinkModel(const LinkModel *link)
const std::vector< GroupState > & getGroupStates() const
std::vector< const JointModel * > active_joint_model_vector_const_
The vector of joints in the model, in the order they appear in the state vector.
void buildGroupStates(const srdf::Model &srdf_model)
Given a SRDF model describing the groups, build the default states defined in the SRDF...
std::vector< const LinkModel * > link_models_with_collision_geometry_vector_
Only links that have collision geometry specified.
std::vector< int > common_joint_roots_
For every two joints, the index of the common root for thw joints is stored.
JointModel * buildRecursive(LinkModel *parent, const urdf::Link *link, const srdf::Model &srdf_model)
(This function is mostly intended for internal use). Given a parent link, build up (recursively)...
void setVariableBounds(const std::string &variable, const VariableBounds &bounds)
Set the lower and upper bounds for a variable. Throw an exception if the variable was not found...
bool satisfiesPositionBounds(const double *state, double margin=0.0) const
JointType getType() const
Get the type of joint.
void setVisualMesh(const std::string &visual_mesh, const Eigen::Affine3d &origin, const Eigen::Vector3d &scale)
double getMaximumExtent() const
void setPassive(bool flag)
virtual unsigned int getStateSpaceDimension() const =0
Get the dimension of the state space that corresponds to this joint.
void setDistanceFactor(double factor)
Set the factor that should be applied to the value returned by distance() when that value is used in ...
const std::vector< EndEffector > & getEndEffectors() const
bool hasJointModelGroup(const std::string &group) const
Check if the JointModelGroup group exists.
std::vector< std::string > link_model_names_with_collision_geometry_vector_
The vector of link names that corresponds to link_models_with_collision_geometry_vector_.
void getVariableDefaultPositions(double *values) const
Compute the default values for a RobotState.
std::shared_ptr< const Shape > ShapeConstPtr
const JointModel * getMimic() const
Get the joint this one is mimicking.