43 #include <srdfdom/srdf_writer.h>                    
   61 static const std::string JOINT_LIMITS_FILE = 
"config/joint_limits.yaml";
 
   62 static const std::string CARTESIAN_LIMITS_FILE = 
"config/pilz_cartesian_limits.yaml";
 
   74   void loadPrevious(
const std::filesystem::path& package_path, 
const YAML::Node& node) 
override;
 
   78   void loadSRDFFile(
const std::filesystem::path& package_path, 
const std::filesystem::path& relative_path);
 
   79   void loadSRDFFile(
const std::filesystem::path& srdf_file_path,
 
   80                     const std::vector<std::string>& xacro_args = std::vector<std::string>());
 
   98     srdf_.no_default_collision_links_.clear();
 
   99     srdf_.enabled_collision_pairs_.clear();
 
  100     srdf_.disabled_collision_pairs_.clear();
 
  105     return srdf_.disabled_collision_pairs_;
 
  110     return srdf_.end_effectors_;
 
  115     return srdf_.groups_;
 
  120     std::vector<std::string> group_names;
 
  121     for (
const srdf::Model::Group& 
group : 
srdf_.groups_)
 
  123       group_names.push_back(
group.name_);
 
  130     return srdf_.group_states_;
 
  135     return srdf_.virtual_joints_;
 
  140     return srdf_.passive_joints_;
 
  149   void removePoseByName(
const std::string& pose_name, 
const std::string& group_name);
 
  151   std::vector<std::string> 
getJointNames(
const std::string& group_name, 
bool include_multi_dof = 
true,
 
  152                                          bool include_passive = 
true);
 
  169       return "SRDF (<a href='http://www.ros.org/wiki/srdf'>Semantic Robot Description Format</a>) is a " 
  170              "representation of semantic information about robots. This format is intended to represent " 
  171              "information about the robot that is not in the URDF file, but it is useful for a variety of " 
  172              "applications. The intention is to include information that has a semantic aspect to it.";
 
  182       std::filesystem::path path = 
getPath();
 
  202       return JOINT_LIMITS_FILE;
 
  207       return "Contains additional information about joints that appear in your planning groups that is not " 
  208              "contained in the URDF, as well as allowing you to set maximum and minimum limits for velocity " 
  209              "and acceleration than those contained in your URDF. This information is used by our trajectory " 
  210              "filtering system to assign reasonable velocities and timing for the trajectory before it is " 
  211              "passed to the robot's controllers.";
 
  219     bool writeYaml(YAML::Emitter& emitter) 
override;
 
  228     using TemplatedGeneratedFile::TemplatedGeneratedFile;
 
  232       return CARTESIAN_LIMITS_FILE;
 
  237       return getSharePath(
"moveit_setup_framework") / 
"templates" / CARTESIAN_LIMITS_FILE;
 
  242       return "Cartesian velocity for planning in the workspace." 
  243              "The velocity is used by pilz industrial motion planner as maximum velocity for cartesian " 
  244              "planning requests scaled by the velocity scaling factor of an individual planning request.";
 
  254                     std::vector<GeneratedFilePtr>& files)
 override 
  256     files.push_back(std::make_shared<GeneratedSRDF>(package_path, last_gen_time, *
this));
 
  257     files.push_back(std::make_shared<GeneratedJointLimits>(package_path, last_gen_time, *
this));
 
  258     files.push_back(std::make_shared<GeneratedCartesianLimits>(package_path, last_gen_time));
 
  263   bool write(
const std::filesystem::path& path)
 
  265     return srdf_.writeSRDF(path.string());
 
Container for the logic for a single file to appear in MoveIt configuration package.
 
std::filesystem::path getPath() const
Returns the fully qualified path to this file.
 
std::filesystem::path getRelativePath() const override
Returns the path relative to the configuration package root.
 
std::string getDescription() const override
Returns an English description of this file's purpose.
 
std::filesystem::path getTemplatePath() const override
Returns the full path to the template file.
 
bool hasChanges() const override
Returns true if this file will have changes when it is written to file.
 
bool hasChanges() const override
Returns true if this file will have changes when it is written to file.
 
std::string getDescription() const override
Returns an English description of this file's purpose.
 
std::filesystem::path getRelativePath() const override
Returns the path relative to the configuration package root.
 
GeneratedJointLimits(const std::filesystem::path &package_path, const GeneratedTime &last_gen_time, SRDFConfig &parent)
 
bool writeYaml(YAML::Emitter &emitter) override
 
std::filesystem::path getRelativePath() const override
Returns the path relative to the configuration package root.
 
std::string getDescription() const override
Returns an English description of this file's purpose.
 
bool hasChanges() const override
Returns true if this file will have changes when it is written to file.
 
GeneratedSRDF(const std::filesystem::path &package_path, const GeneratedTime &last_gen_time, SRDFConfig &parent)
 
bool write() override
Writes the file to disk.
 
void updateRobotModel(long changed_information=0L)
 
std::vector< srdf::Model::VirtualJoint > & getVirtualJoints()
 
bool isConfigured() const override
Return true if this part of the configuration is completely set up.
 
std::vector< srdf::Model::PassiveJoint > & getPassiveJoints()
 
void collectFiles(const std::filesystem::path &package_path, const GeneratedTime &last_gen_time, std::vector< GeneratedFilePtr > &files) override
Collect the files generated by this configuration and add them to the vector.
 
unsigned long getChangeMask() const
 
srdf::SRDFWriter srdf_
SRDF Data and Writer.
 
planning_scene::PlanningScenePtr planning_scene_
Shared planning scene.
 
void removePoseByName(const std::string &pose_name, const std::string &group_name)
 
std::shared_ptr< urdf::Model > urdf_model_
 
planning_scene::PlanningScenePtr getPlanningScene()
Provide a shared planning scene.
 
std::filesystem::path getPath() const
 
bool write(const std::filesystem::path &path)
 
std::filesystem::path srdf_pkg_relative_path_
Path relative to loaded configuration package.
 
std::string getChildOfJoint(const std::string &joint_name) const
Return the name of the child link of a joint.
 
moveit::core::RobotModelPtr getRobotModel() const
 
void clearCollisionData()
 
moveit::core::RobotModelPtr robot_model_
 
std::vector< std::string > getJointNames(const std::string &group_name, bool include_multi_dof=true, bool include_passive=true)
 
std::filesystem::path srdf_path_
Full file-system path to srdf.
 
std::vector< srdf::Model::CollisionPair > & getDisabledCollisions()
 
void loadSRDFFile(const std::filesystem::path &package_path, const std::filesystem::path &relative_path)
Load SRDF File.
 
YAML::Node saveToYaml() const override
Optionally save "meta" information for saving in the .setup_assistant yaml file.
 
std::vector< srdf::Model::EndEffector > & getEndEffectors()
 
std::vector< std::string > getGroupNames() const
 
void onInit() override
Overridable initialization method.
 
std::vector< srdf::Model::GroupState > & getGroupStates()
 
std::vector< std::string > getLinkNames() const
 
void collectVariables(std::vector< TemplateVariable > &variables) override
Collect key/value pairs for use in templates.
 
std::vector< srdf::Model::Group > & getGroups()
 
void loadPrevious(const std::filesystem::path &package_path, const YAML::Node &node) override
Loads the configuration from an existing MoveIt configuration.
 
where all the data for each part of the configuration is stored.
 
Specialization of GeneratedFile for generating a text file from a template.
 
std::filesystem::path getSharePath(const std::string &package_name)
Return a path for the given package's share folder.
 
bool createParentFolders(const std::filesystem::path &file_path)
Create parent folders (recursively)
 
std::filesystem::file_time_type GeneratedTime