#include <moveit_config_data.h>
Public Member Functions | |
| std::string | appendPaths (const std::string &path1, const std::string &path2) |
| std::string | decideProjectionJoints (std::string planning_group) |
| Decide the best two joints to be used for the projection evaluator. | |
| srdf::Model::Group * | findGroupByName (const std::string &name) |
| planning_scene::PlanningScenePtr | getPlanningScene () |
| Provide a shared planning scene. | |
| robot_model::RobotModelConstPtr | getRobotModel () |
| Provide a shared kinematic model loader. | |
| bool | inputKinematicsYAML (const std::string &file_path) |
| bool | inputSetupAssistantYAML (const std::string &file_path) |
| void | loadAllowedCollisionMatrix () |
| Load the allowed collision matrix from the SRDF's list of link pairs. | |
| MoveItConfigData () | |
| bool | outputJointLimitsYAML (const std::string &file_path) |
| bool | outputKinematicsYAML (const std::string &file_path) |
| bool | outputOMPLPlanningYAML (const std::string &file_path) |
| bool | outputSetupAssistantFile (const std::string &file_path) |
| void | updateRobotModel () |
| Update the Kinematic Model with latest SRDF modifications. | |
| ~MoveItConfigData () | |
Public Attributes | |
| collision_detection::AllowedCollisionMatrix | allowed_collision_matrix_ |
| Allowed collision matrix for robot poses. | |
| std::time_t | config_pkg_generated_timestamp_ |
| Timestamp when configuration package was generated, if it was previously generated. | |
| std::string | config_pkg_path_ |
| Loaded configuration package path - if an existing package was loaded, holds that path. | |
| bool | debug_ |
| Is this application in debug mode? | |
| std::map< std::string, GroupMetaData > | group_meta_data_ |
| Planning groups extra data not found in srdf but used in config files. | |
| std::string | setup_assistant_path_ |
| Setup Assistants package's path for when we use its templates. | |
| SRDFWriterPtr | srdf_ |
| SRDF Data and Writer. | |
| std::string | srdf_path_ |
| Full file-system path to srdf. | |
| std::string | srdf_pkg_relative_path_ |
| Path relative to loaded configuration package. | |
| std::string | template_package_path_ |
| Location that moveit_setup_assistant stores its templates. | |
| bool | urdf_from_xacro_ |
| Flag indicating whether the URDF was loaded from .xacro format. | |
| boost::shared_ptr< urdf::Model > | urdf_model_ |
| URDF robot model. | |
| std::string | urdf_path_ |
| Full file-system path to urdf. | |
| std::string | urdf_pkg_name_ |
| Name of package containig urdf (note: this may be empty b/c user may not have urdf in pkg) | |
| std::string | urdf_pkg_relative_path_ |
| Path relative to urdf package (note: this may be same as urdf_path_) | |
Private Attributes | |
| robot_model::RobotModelPtr | kin_model_ |
| robot_model::RobotModelConstPtr | kin_model_const_ |
| planning_scene::PlanningScenePtr | planning_scene_ |
Definition at line 87 of file moveit_config_data.h.
Definition at line 68 of file moveit_config_data.cpp.
Definition at line 89 of file moveit_config_data.cpp.
| std::string moveit_setup_assistant::MoveItConfigData::appendPaths | ( | const std::string & | path1, |
| const std::string & | path2 | ||
| ) |
Helper Function for joining a file path and a file name, or two file paths, etc, in a cross-platform way
| path1 | first half of path |
| path2 | second half of path, or filename |
Definition at line 607 of file moveit_config_data.cpp.
| std::string moveit_setup_assistant::MoveItConfigData::decideProjectionJoints | ( | std::string | planning_group | ) |
Decide the best two joints to be used for the projection evaluator.
| planning_group | name of group to use |
Definition at line 413 of file moveit_config_data.cpp.
| srdf::Model::Group * moveit_setup_assistant::MoveItConfigData::findGroupByName | ( | const std::string & | name | ) |
Find the associated group by name
| name | - name of data to find in datastructure |
Definition at line 614 of file moveit_config_data.cpp.
Provide a shared planning scene.
Definition at line 129 of file moveit_config_data.cpp.
Provide a shared kinematic model loader.
Definition at line 96 of file moveit_config_data.cpp.
| bool moveit_setup_assistant::MoveItConfigData::inputKinematicsYAML | ( | const std::string & | file_path | ) |
Input kinematics.yaml file for editing its values
| file_path | path to kinematics.yaml in the input package |
Definition at line 447 of file moveit_config_data.cpp.
| bool moveit_setup_assistant::MoveItConfigData::inputSetupAssistantYAML | ( | const std::string & | file_path | ) |
Input .setup_assistant file - contains data used for the MoveIt Setup Assistant
| file_path | path to .setup_assistant file |
Definition at line 525 of file moveit_config_data.cpp.
Load the allowed collision matrix from the SRDF's list of link pairs.
Definition at line 145 of file moveit_config_data.cpp.
| bool moveit_setup_assistant::MoveItConfigData::outputJointLimitsYAML | ( | const std::string & | file_path | ) |
Definition at line 334 of file moveit_config_data.cpp.
| bool moveit_setup_assistant::MoveItConfigData::outputKinematicsYAML | ( | const std::string & | file_path | ) |
Definition at line 280 of file moveit_config_data.cpp.
| bool moveit_setup_assistant::MoveItConfigData::outputOMPLPlanningYAML | ( | const std::string & | file_path | ) |
Definition at line 208 of file moveit_config_data.cpp.
| bool moveit_setup_assistant::MoveItConfigData::outputSetupAssistantFile | ( | const std::string & | file_path | ) |
Update the Kinematic Model with latest SRDF modifications.
Definition at line 111 of file moveit_config_data.cpp.
| collision_detection::AllowedCollisionMatrix moveit_setup_assistant::MoveItConfigData::allowed_collision_matrix_ |
Allowed collision matrix for robot poses.
Definition at line 147 of file moveit_config_data.h.
Timestamp when configuration package was generated, if it was previously generated.
Definition at line 150 of file moveit_config_data.h.
Loaded configuration package path - if an existing package was loaded, holds that path.
Definition at line 138 of file moveit_config_data.h.
Is this application in debug mode?
Definition at line 144 of file moveit_config_data.h.
| std::map<std::string, GroupMetaData> moveit_setup_assistant::MoveItConfigData::group_meta_data_ |
Planning groups extra data not found in srdf but used in config files.
Definition at line 132 of file moveit_config_data.h.
Definition at line 223 of file moveit_config_data.h.
robot_model::RobotModelConstPtr moveit_setup_assistant::MoveItConfigData::kin_model_const_ [private] |
Definition at line 224 of file moveit_config_data.h.
planning_scene::PlanningScenePtr moveit_setup_assistant::MoveItConfigData::planning_scene_ [private] |
Definition at line 227 of file moveit_config_data.h.
Setup Assistants package's path for when we use its templates.
Definition at line 135 of file moveit_config_data.h.
SRDF Data and Writer.
Definition at line 125 of file moveit_config_data.h.
Full file-system path to srdf.
Definition at line 119 of file moveit_config_data.h.
Path relative to loaded configuration package.
Definition at line 122 of file moveit_config_data.h.
Location that moveit_setup_assistant stores its templates.
Definition at line 141 of file moveit_config_data.h.
Flag indicating whether the URDF was loaded from .xacro format.
Definition at line 109 of file moveit_config_data.h.
| boost::shared_ptr<urdf::Model> moveit_setup_assistant::MoveItConfigData::urdf_model_ |
URDF robot model.
Definition at line 112 of file moveit_config_data.h.
Full file-system path to urdf.
Definition at line 100 of file moveit_config_data.h.
Name of package containig urdf (note: this may be empty b/c user may not have urdf in pkg)
Definition at line 103 of file moveit_config_data.h.
Path relative to urdf package (note: this may be same as urdf_path_)
Definition at line 106 of file moveit_config_data.h.