moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <srdf_config.hpp>
Classes | |
class | GeneratedCartesianLimits |
class | GeneratedJointLimits |
class | GeneratedSRDF |
Public Member Functions | |
void | onInit () override |
Overridable initialization method. More... | |
bool | isConfigured () const override |
Return true if this part of the configuration is completely set up. More... | |
void | loadPrevious (const std::filesystem::path &package_path, const YAML::Node &node) override |
Loads the configuration from an existing MoveIt configuration. More... | |
YAML::Node | saveToYaml () const override |
Optionally save "meta" information for saving in the .setup_assistant yaml file. More... | |
void | loadSRDFFile (const std::filesystem::path &package_path, const std::filesystem::path &relative_path) |
Load SRDF File. More... | |
void | loadSRDFFile (const std::filesystem::path &srdf_file_path, const std::vector< std::string > &xacro_args=std::vector< std::string >()) |
moveit::core::RobotModelPtr | getRobotModel () const |
planning_scene::PlanningScenePtr | getPlanningScene () |
Provide a shared planning scene. More... | |
void | updateRobotModel (long changed_information=0L) |
std::vector< std::string > | getLinkNames () const |
void | clearCollisionData () |
std::vector< srdf::Model::CollisionPair > & | getDisabledCollisions () |
std::vector< srdf::Model::EndEffector > & | getEndEffectors () |
std::vector< srdf::Model::Group > & | getGroups () |
std::vector< std::string > | getGroupNames () const |
std::vector< srdf::Model::GroupState > & | getGroupStates () |
std::vector< srdf::Model::VirtualJoint > & | getVirtualJoints () |
std::vector< srdf::Model::PassiveJoint > & | getPassiveJoints () |
std::string | getChildOfJoint (const std::string &joint_name) const |
Return the name of the child link of a joint. More... | |
void | removePoseByName (const std::string &pose_name, const std::string &group_name) |
std::vector< std::string > | getJointNames (const std::string &group_name, bool include_multi_dof=true, bool include_passive=true) |
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. More... | |
void | collectVariables (std::vector< TemplateVariable > &variables) override |
Collect key/value pairs for use in templates. More... | |
bool | write (const std::filesystem::path &path) |
std::filesystem::path | getPath () const |
unsigned long | getChangeMask () const |
Public Member Functions inherited from moveit_setup::SetupConfig | |
SetupConfig ()=default | |
SetupConfig (const SetupConfig &)=default | |
SetupConfig (SetupConfig &&)=default | |
SetupConfig & | operator= (const SetupConfig &)=default |
SetupConfig & | operator= (SetupConfig &&)=default |
virtual | ~SetupConfig ()=default |
void | initialize (const std::shared_ptr< DataWarehouse > &config_data, const rclcpp::Node::SharedPtr &parent_node, const std::string &name) |
Called after construction to initialize the step. More... | |
const std::string & | getName () |
The name for this part of the configuration. More... | |
virtual void | collectDependencies (std::set< std::string > &) const |
Collect the package dependencies generated by this configuration. More... | |
Protected Member Functions | |
void | getRelativePath () |
void | loadURDFModel () |
Protected Attributes | |
std::filesystem::path | srdf_path_ |
Full file-system path to srdf. More... | |
std::filesystem::path | srdf_pkg_relative_path_ |
Path relative to loaded configuration package. More... | |
srdf::SRDFWriter | srdf_ |
SRDF Data and Writer. More... | |
std::shared_ptr< urdf::Model > | urdf_model_ |
moveit::core::RobotModelPtr | robot_model_ |
planning_scene::PlanningScenePtr | planning_scene_ |
Shared planning scene. More... | |
unsigned long | changes_ |
Protected Attributes inherited from moveit_setup::SetupConfig | |
std::shared_ptr< DataWarehouse > | config_data_ |
rclcpp::Node::SharedPtr | parent_node_ |
std::string | name_ |
std::shared_ptr< rclcpp::Logger > | logger_ |
Definition at line 64 of file srdf_config.hpp.
|
inline |
Definition at line 96 of file srdf_config.hpp.
|
inlineoverridevirtual |
Collect the files generated by this configuration and add them to the vector.
[in] | package_path | the path to the root of the config package |
[in] | last_gen_time | The time (if any) when the config package was last generated @parma[out] files Where to put the new generated files |
Reimplemented from moveit_setup::SetupConfig.
Definition at line 253 of file srdf_config.hpp.
|
overridevirtual |
Collect key/value pairs for use in templates.
[out] | variables | Where to put the new Variables |
Reimplemented from moveit_setup::SetupConfig.
Definition at line 215 of file srdf_config.cpp.
|
inline |
std::string moveit_setup::SRDFConfig::getChildOfJoint | ( | const std::string & | joint_name | ) | const |
Return the name of the child link of a joint.
Definition at line 168 of file srdf_config.cpp.
|
inline |
Definition at line 103 of file srdf_config.hpp.
|
inline |
Definition at line 108 of file srdf_config.hpp.
|
inline |
Definition at line 118 of file srdf_config.hpp.
|
inline |
Definition at line 113 of file srdf_config.hpp.
|
inline |
Definition at line 128 of file srdf_config.hpp.
std::vector< std::string > moveit_setup::SRDFConfig::getJointNames | ( | const std::string & | group_name, |
bool | include_multi_dof = true , |
||
bool | include_passive = true |
||
) |
std::vector< std::string > moveit_setup::SRDFConfig::getLinkNames | ( | ) | const |
Definition at line 158 of file srdf_config.cpp.
|
inline |
Definition at line 138 of file srdf_config.hpp.
|
inline |
Definition at line 268 of file srdf_config.hpp.
planning_scene::PlanningScenePtr moveit_setup::SRDFConfig::getPlanningScene | ( | ) |
Provide a shared planning scene.
Definition at line 145 of file srdf_config.cpp.
|
protected |
Definition at line 110 of file srdf_config.cpp.
|
inline |
|
inline |
Definition at line 133 of file srdf_config.hpp.
|
inlineoverridevirtual |
Return true if this part of the configuration is completely set up.
Reimplemented from moveit_setup::SetupConfig.
Definition at line 69 of file srdf_config.hpp.
|
overridevirtual |
Loads the configuration from an existing MoveIt configuration.
The data can be loaded directly from files in the configuration via the package path.
Certain other pieces of "meta" information may be stored in the .setup_assistant yaml file in the root of the configuration. If there is a node in that file that matches this config's name, it is passed in as an argument.
package_path | The path to the root folder of the configuration. |
Reimplemented from moveit_setup::SetupConfig.
Definition at line 47 of file srdf_config.cpp.
void moveit_setup::SRDFConfig::loadSRDFFile | ( | const std::filesystem::path & | package_path, |
const std::filesystem::path & | relative_path | ||
) |
Load SRDF File.
Definition at line 76 of file srdf_config.cpp.
void moveit_setup::SRDFConfig::loadSRDFFile | ( | const std::filesystem::path & | srdf_file_path, |
const std::vector< std::string > & | xacro_args = std::vector<std::string>() |
||
) |
|
protected |
|
overridevirtual |
Overridable initialization method.
Reimplemented from moveit_setup::SetupConfig.
Definition at line 41 of file srdf_config.cpp.
void moveit_setup::SRDFConfig::removePoseByName | ( | const std::string & | pose_name, |
const std::string & | group_name | ||
) |
|
overridevirtual |
Optionally save "meta" information for saving in the .setup_assistant yaml file.
Reimplemented from moveit_setup::SetupConfig.
Definition at line 56 of file srdf_config.cpp.
void moveit_setup::SRDFConfig::updateRobotModel | ( | long | changed_information = 0L | ) |
Update the robot model with the new SRDF, AND mark the changes that have been made to the model changed_information should be composed of InformationFields
Definition at line 119 of file srdf_config.cpp.
|
inline |
|
protected |
Definition at line 302 of file srdf_config.hpp.
|
protected |
Shared planning scene.
Definition at line 299 of file srdf_config.hpp.
|
protected |
Definition at line 296 of file srdf_config.hpp.
|
protected |
SRDF Data and Writer.
Definition at line 292 of file srdf_config.hpp.
|
protected |
Full file-system path to srdf.
Definition at line 286 of file srdf_config.hpp.
|
protected |
Path relative to loaded configuration package.
Definition at line 289 of file srdf_config.hpp.
|
protected |
Definition at line 294 of file srdf_config.hpp.