71 return "Planning Groups";
91 void renameGroup(
const std::string& old_group_name,
const std::string& new_group_name);
97 void setJoints(
const std::string& group_name,
const std::vector<std::string>& joint_names);
102 void setLinks(
const std::string& group_name,
const std::vector<std::string>& link_names);
108 void setChain(
const std::string& group_name,
const std::string& base,
const std::string& tip);
114 void setSubgroups(
const std::string& selected_group_name,
const std::vector<std::string>& subgroups);
133 return srdf_config_->getRobotModel()->getJointModelNames();
138 return srdf_config_->getRobotModel()->getLinkModelNames();
142 std::string
getJointType(
const std::string& joint_name)
const;
144 std::vector<std::string>
getPosesByGroup(
const std::string& group_name)
const;
A link from the robot. Contains the constant transform applied to the link and its geometry.
const std::string & getName() const
The name of this link.
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...
std::vector< LinkNameTree > children
std::vector< srdf::Model::Group > & getContainer() override
Returns the reference to the vector in the SRDF.
void setChain(const std::string &group_name, const std::string &base, const std::string &tip)
Set the specified group's kinematic chain.
void onInit() override
Overridable initialization method.
const std::vector< std::string > & getLinkNames() const
void setLinks(const std::string &group_name, const std::vector< std::string > &link_names)
Set the specified group's link names.
void setSubgroups(const std::string &selected_group_name, const std::vector< std::string > &subgroups)
Set the specified group's subgroups.
const std::vector< std::string > & getJointNames() const
std::vector< srdf::Model::Group > & getGroups()
void renameGroup(const std::string &old_group_name, const std::string &new_group_name)
std::string getName() const override
Returns the name of the setup step.
std::string getChildOfJoint(const std::string &joint_name) const
void deleteGroup(const std::string &group_name)
std::vector< std::string > getPosesByGroup(const std::string &group_name) const
std::string getJointType(const std::string &joint_name) const
std::shared_ptr< GroupMetaConfig > group_meta_config_
std::vector< std::string > getGroupNames() const
std::vector< std::string > getKinematicPlanners() const
InformationFields getInfoField() const override
Returns the info field associated with this part of the SRDF.
std::vector< std::string > getOMPLPlanners() const
std::vector< std::string > getEndEffectorsByGroup(const std::string &group_name) const
void setJoints(const std::string &group_name, const std::vector< std::string > &joint_names)
Set the specified group's joint names.
const GroupMetaData & getMetaData(const std::string &group_name) const
LinkNameTree getLinkNameTree() const
void setMetaData(const std::string &group_name, const GroupMetaData &meta_data)
std::shared_ptr< SRDFConfig > srdf_config_
This class provides a number of standard operations based on srdf's vector members.
LinkNameTree buildLinkNameTree(const moveit::core::LinkModel *link)