Classes | Public Types | Public Member Functions | Static Public Member Functions | Public Attributes | Private Attributes | List of all members
moveit_setup_assistant::MoveItConfigData Class Reference

This class is shared with all widgets and contains the common configuration data needed for generating each robot's MoveIt configuration package. More...

#include <moveit_config_data.h>

Classes

struct  JointModelCompare
 Custom std::set comparator, used for sorting the joint_limits.yaml file into alphabetical order. More...
 

Public Types

enum  InformationFields {
  COLLISIONS = 1 << 1, VIRTUAL_JOINTS = 1 << 2, GROUPS = 1 << 3, GROUP_CONTENTS = 1 << 4,
  GROUP_KINEMATICS = 1 << 5, POSES = 1 << 6, END_EFFECTORS = 1 << 7, PASSIVE_JOINTS = 1 << 8,
  SIMULATION = 1 << 9, AUTHOR_INFO = 1 << 10, SENSORS_CONFIG = 1 << 11, SRDF = COLLISIONS | VIRTUAL_JOINTS | GROUPS | GROUP_CONTENTS | POSES | END_EFFECTORS | PASSIVE_JOINTS
}
 

Public Member Functions

bool addController (const ControllerConfig &new_controller)
 Adds a controller to controller_configs_ vector. More...
 
bool addDefaultControllers (const std::string &controller_type="effort_controllers/JointTrajectoryController")
 Add a Follow Joint Trajectory action Controller for each Planning Group. More...
 
void addGenericParameterToSensorPluginConfig (const std::string &name, const std::string &value="", const std::string &comment="")
 Used for adding a sensor plugin configuation prameter to the sensor plugin configuration parameter list. More...
 
std::string appendPaths (const std::string &path1, const std::string &path2)
 
void clearSensorPluginConfig ()
 Clear the sensor plugin configuration parameter list. More...
 
bool createFullSRDFPath (const std::string &package_path)
 Make the full SRDF path using the loaded .setup_assistant data. More...
 
bool createFullURDFPath ()
 Make the full URDF path using the loaded .setup_assistant data. More...
 
std::string decideProjectionJoints (const std::string &planning_group)
 Decide the best two joints to be used for the projection evaluator. More...
 
bool deleteController (const std::string &controller_name)
 
bool extractPackageNameFromPath (const std::string &path, std::string &package_name, std::string &relative_filepath) const
 
ControllerConfigfindControllerByName (const std::string &controller_name)
 
srdf::Model::GroupfindGroupByName (const std::string &name)
 
std::vector< ControllerConfig > & getControllers ()
 Gets controller_configs_ vector. More...
 
srdf::Model::GroupState getDefaultStartPose ()
 Helper function to get the default start pose for moveit_sim_hw_interface. More...
 
std::map< std::string, double > getInitialJoints () const
 
std::string getJointHardwareInterface (const std::string &joint_name)
 Helper function to get the controller that is controlling the joint. More...
 
std::vector< OMPLPlannerDescriptiongetOMPLPlanners () const
 
planning_scene::PlanningScenePtr getPlanningScene ()
 Provide a shared planning scene. More...
 
moveit::core::RobotModelConstPtr getRobotModel ()
 Provide a shared kinematic model loader. More...
 
const std::vector< std::map< std::string, GenericParameter > > & getSensorPluginConfig () const
 Used for adding a sensor plugin configuation parameter to the sensor plugin configuration parameter list. More...
 
bool getSetupAssistantYAMLPath (std::string &path)
 
void input3DSensorsYAML (const std::string &file_path)
 Load perception sensor config (sensors_3d.yaml) into internal data structure. More...
 
bool inputKinematicsYAML (const std::string &file_path)
 
bool inputOMPLYAML (const std::string &file_path)
 
bool inputPlanningContextLaunch (const std::string &file_path)
 
bool inputROSControllersYAML (const std::string &file_path)
 
bool inputSetupAssistantYAML (const std::string &file_path)
 
void loadAllowedCollisionMatrix (const srdf::SRDFWriter &srdf)
 Load the allowed collision matrix from the SRDF's list of link pairs. More...
 
 MoveItConfigData ()
 
bool output3DSensorPluginYAML (const std::string &file_path)
 
bool outputFakeControllersYAML (const std::string &file_path)
 
bool outputGazeboURDFFile (const std::string &file_path)
 
bool outputJointLimitsYAML (const std::string &file_path)
 
bool outputKinematicsYAML (const std::string &file_path)
 
bool outputOMPLPlanningYAML (const std::string &file_path)
 
bool outputROSControllersYAML (const std::string &file_path)
 
bool outputSetupAssistantFile (const std::string &file_path)
 
bool outputSimpleControllersYAML (const std::string &file_path)
 
bool outputSTOMPPlanningYAML (const std::string &file_path)
 
bool parseROSController (const YAML::Node &controller)
 
bool processROSControllers (std::ifstream &input_stream)
 
bool setPackagePath (const std::string &pkg_path)
 
void setRobotModel (const moveit::core::RobotModelPtr &robot_model)
 Load a robot model. More...
 
void updateRobotModel ()
 Update the Kinematic Model with latest SRDF modifications. More...
 
 ~MoveItConfigData ()
 

Static Public Member Functions

static std::vector< std::map< std::string, GenericParameter > > load3DSensorsYAML (const std::string &file_path)
 Load perception sensor config. More...
 

Public Attributes

collision_detection::AllowedCollisionMatrix allowed_collision_matrix_
 Allowed collision matrix for robot poses. More...
 
std::string author_email_
 Email of the author of this config. More...
 
std::string author_name_
 Name of the author of this config. More...
 
unsigned long changes
 
std::time_t config_pkg_generated_timestamp_
 Timestamp when configuration package was generated, if it was previously generated. More...
 
std::string config_pkg_path_
 Loaded configuration package path - if an existing package was loaded, holds that path. More...
 
bool debug_
 Is this application in debug mode? More...
 
std::string gazebo_urdf_string_
 Gazebo URDF robot model string. More...
 
std::map< std::string, GroupMetaDatagroup_meta_data_
 Planning groups extra data not found in srdf but used in config files. More...
 
std::string setup_assistant_path_
 Setup Assistants package's path for when we use its templates. More...
 
srdf::SRDFWriterPtr srdf_
 SRDF Data and Writer. More...
 
std::string srdf_path_
 Full file-system path to srdf. More...
 
std::string srdf_pkg_relative_path_
 Path relative to loaded configuration package. More...
 
std::string template_package_path_
 Location that moveit_setup_assistant stores its templates. More...
 
bool urdf_from_xacro_
 Flag indicating whether the URDF was loaded from .xacro format. More...
 
urdf::ModelSharedPtr urdf_model_
 URDF robot model. More...
 
std::string urdf_path_
 Full file-system path to urdf. More...
 
std::string urdf_pkg_name_
 Name of package containig urdf (note: this may be empty b/c user may not have urdf in pkg) More...
 
std::string urdf_pkg_relative_path_
 Path relative to urdf package (note: this may be same as urdf_path_) More...
 
std::string urdf_string_
 URDF robot model string. More...
 
std::string xacro_args_
 xacro arguments More...
 

Private Attributes

std::vector< ControllerConfigcontroller_configs_
 Controllers config data. More...
 
planning_scene::PlanningScenePtr planning_scene_
 Shared planning scene. More...
 
moveit::core::RobotModelPtr robot_model_
 Shared kinematic model. More...
 
std::vector< std::map< std::string, GenericParameter > > sensors_plugin_config_parameter_list_
 Sensor plugin configuration parameter list, each sensor plugin type is a map. More...
 

Detailed Description

This class is shared with all widgets and contains the common configuration data needed for generating each robot's MoveIt configuration package.

All SRDF data is contained in a subclass of this class - srdf_writer.cpp. This class also contains the functions for writing out the configuration files.

Definition at line 219 of file moveit_config_data.h.

Member Enumeration Documentation

◆ InformationFields

Enumerator
COLLISIONS 
VIRTUAL_JOINTS 
GROUPS 
GROUP_CONTENTS 
GROUP_KINEMATICS 
POSES 
END_EFFECTORS 
PASSIVE_JOINTS 
SIMULATION 
AUTHOR_INFO 
SENSORS_CONFIG 
SRDF 

Definition at line 226 of file moveit_config_data.h.

Constructor & Destructor Documentation

◆ MoveItConfigData()

MoveItConfigData::MoveItConfigData ( )

Definition at line 95 of file moveit_config_data.cpp.

◆ ~MoveItConfigData()

MoveItConfigData::~MoveItConfigData ( )
default

Member Function Documentation

◆ addController()

bool MoveItConfigData::addController ( const ControllerConfig new_controller)

Adds a controller to controller_configs_ vector.

Parameters
new_controllera new Controller to add
Returns
true if inserted correctly

Definition at line 1987 of file moveit_config_data.cpp.

◆ addDefaultControllers()

bool MoveItConfigData::addDefaultControllers ( const std::string &  controller_type = "effort_controllers/JointTrajectoryController")

Add a Follow Joint Trajectory action Controller for each Planning Group.

Returns
true if controllers were added to the controller_configs_ data structure

Definition at line 1644 of file moveit_config_data.cpp.

◆ addGenericParameterToSensorPluginConfig()

void MoveItConfigData::addGenericParameterToSensorPluginConfig ( const std::string &  name,
const std::string &  value = "",
const std::string &  comment = "" 
)

Used for adding a sensor plugin configuation prameter to the sensor plugin configuration parameter list.

Definition at line 2002 of file moveit_config_data.cpp.

◆ appendPaths()

std::string 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

Parameters
path1first half of path
path2second half of path, or filename
Returns
string resulting combined paths

Definition at line 1921 of file moveit_config_data.cpp.

◆ clearSensorPluginConfig()

void MoveItConfigData::clearSensorPluginConfig ( )

Clear the sensor plugin configuration parameter list.

Definition at line 2016 of file moveit_config_data.cpp.

◆ createFullSRDFPath()

bool MoveItConfigData::createFullSRDFPath ( const std::string &  package_path)

Make the full SRDF path using the loaded .setup_assistant data.

Definition at line 1789 of file moveit_config_data.cpp.

◆ createFullURDFPath()

bool MoveItConfigData::createFullURDFPath ( )

Make the full URDF path using the loaded .setup_assistant data.

Definition at line 1757 of file moveit_config_data.cpp.

◆ decideProjectionJoints()

std::string MoveItConfigData::decideProjectionJoints ( const std::string &  planning_group)

Decide the best two joints to be used for the projection evaluator.

Parameters
planning_groupname of group to use
Returns
string - value to insert into yaml file

Definition at line 1335 of file moveit_config_data.cpp.

◆ deleteController()

bool MoveItConfigData::deleteController ( const std::string &  controller_name)

Delete controller by name

Parameters
controller_name- name of controller to delete
Returns
true if deleted, false if not found

Definition at line 1969 of file moveit_config_data.cpp.

◆ extractPackageNameFromPath()

bool MoveItConfigData::extractPackageNameFromPath ( const std::string &  path,
std::string &  package_name,
std::string &  relative_filepath 
) const

determine the package name containing a given file path

Parameters
pathto a file
package_nameholds the ros package name if found
relative_filepathholds the relative path of the file to the package root
Returns
whether the file belongs to a known package

Definition at line 1707 of file moveit_config_data.cpp.

◆ findControllerByName()

ControllerConfig * MoveItConfigData::findControllerByName ( const std::string &  controller_name)

Find the associated controller by name

Parameters
controller_name- name of controller to find in datastructure
Returns
pointer to data in datastructure

Definition at line 1954 of file moveit_config_data.cpp.

◆ findGroupByName()

srdf::Model::Group * MoveItConfigData::findGroupByName ( const std::string &  name)

Find the associated group by name

Parameters
name- name of data to find in datastructure
Returns
pointer to data in datastructure

Definition at line 1928 of file moveit_config_data.cpp.

◆ getControllers()

std::vector<ControllerConfig>& moveit_setup_assistant::MoveItConfigData::getControllers ( )
inline

Gets controller_configs_ vector.

Returns
pointer to controller_configs_

Definition at line 485 of file moveit_config_data.h.

◆ getDefaultStartPose()

srdf::Model::GroupState MoveItConfigData::getDefaultStartPose ( )

Helper function to get the default start pose for moveit_sim_hw_interface.

Definition at line 1036 of file moveit_config_data.cpp.

◆ getInitialJoints()

std::map< std::string, double > MoveItConfigData::getInitialJoints ( ) const

Definition at line 665 of file moveit_config_data.cpp.

◆ getJointHardwareInterface()

std::string MoveItConfigData::getJointHardwareInterface ( const std::string &  joint_name)

Helper function to get the controller that is controlling the joint.

Returns
controller type

Definition at line 550 of file moveit_config_data.cpp.

◆ getOMPLPlanners()

std::vector< OMPLPlannerDescription > MoveItConfigData::getOMPLPlanners ( ) const

Definition at line 687 of file moveit_config_data.cpp.

◆ getPlanningScene()

planning_scene::PlanningScenePtr MoveItConfigData::getPlanningScene ( )

Provide a shared planning scene.

Definition at line 159 of file moveit_config_data.cpp.

◆ getRobotModel()

moveit::core::RobotModelConstPtr MoveItConfigData::getRobotModel ( )

Provide a shared kinematic model loader.

Definition at line 128 of file moveit_config_data.cpp.

◆ getSensorPluginConfig()

const std::vector<std::map<std::string, GenericParameter> >& moveit_setup_assistant::MoveItConfigData::getSensorPluginConfig ( ) const
inline

Used for adding a sensor plugin configuation parameter to the sensor plugin configuration parameter list.

Definition at line 520 of file moveit_config_data.h.

◆ getSetupAssistantYAMLPath()

bool MoveItConfigData::getSetupAssistantYAMLPath ( std::string &  path)

Resolve path to .setup_assistant file

Parameters
pathresolved path
Returns
true if the path could be resolved

Definition at line 1746 of file moveit_config_data.cpp.

◆ input3DSensorsYAML()

void MoveItConfigData::input3DSensorsYAML ( const std::string &  file_path)

Load perception sensor config (sensors_3d.yaml) into internal data structure.

Definition at line 1855 of file moveit_config_data.cpp.

◆ inputKinematicsYAML()

bool MoveItConfigData::inputKinematicsYAML ( const std::string &  file_path)

Input kinematics.yaml file for editing its values

Parameters
file_pathpath to kinematics.yaml in the input package
Returns
true if the file was read correctly

Definition at line 1423 of file moveit_config_data.cpp.

◆ inputOMPLYAML()

bool MoveItConfigData::inputOMPLYAML ( const std::string &  file_path)

Input ompl_planning.yaml file for editing its values

Parameters
file_pathpath to ompl_planning.yaml in the input package
Returns
true if the file was read correctly

Definition at line 1375 of file moveit_config_data.cpp.

◆ inputPlanningContextLaunch()

bool MoveItConfigData::inputPlanningContextLaunch ( const std::string &  file_path)

Input planning_context.launch for editing its values

Parameters
file_pathpath to planning_context.launch in the input package
Returns
true if the file was read correctly

Definition at line 1474 of file moveit_config_data.cpp.

◆ inputROSControllersYAML()

bool MoveItConfigData::inputROSControllersYAML ( const std::string &  file_path)

Input ros_controllers.yaml file for editing its values

Parameters
file_pathpath to ros_controllers.yaml in the input package
Returns
true if the file was read correctly

Definition at line 1617 of file moveit_config_data.cpp.

◆ inputSetupAssistantYAML()

bool MoveItConfigData::inputSetupAssistantYAML ( const std::string &  file_path)

Input .setup_assistant file - contains data used for the MoveIt Setup Assistant

Parameters
file_pathpath to .setup_assistant file
Returns
true if the file was read correctly

Definition at line 1799 of file moveit_config_data.cpp.

◆ load3DSensorsYAML()

std::vector< std::map< std::string, GenericParameter > > MoveItConfigData::load3DSensorsYAML ( const std::string &  file_path)
static

Load perception sensor config.

Definition at line 1863 of file moveit_config_data.cpp.

◆ loadAllowedCollisionMatrix()

void MoveItConfigData::loadAllowedCollisionMatrix ( const srdf::SRDFWriter srdf)

Load the allowed collision matrix from the SRDF's list of link pairs.

Definition at line 175 of file moveit_config_data.cpp.

◆ output3DSensorPluginYAML()

bool MoveItConfigData::output3DSensorPluginYAML ( const std::string &  file_path)

Definition at line 1198 of file moveit_config_data.cpp.

◆ outputFakeControllersYAML()

bool MoveItConfigData::outputFakeControllersYAML ( const std::string &  file_path)

Definition at line 571 of file moveit_config_data.cpp.

◆ outputGazeboURDFFile()

bool MoveItConfigData::outputGazeboURDFFile ( const std::string &  file_path)

Definition at line 248 of file moveit_config_data.cpp.

◆ outputJointLimitsYAML()

bool MoveItConfigData::outputJointLimitsYAML ( const std::string &  file_path)

Definition at line 1238 of file moveit_config_data.cpp.

◆ outputKinematicsYAML()

bool MoveItConfigData::outputKinematicsYAML ( const std::string &  file_path)

Definition at line 489 of file moveit_config_data.cpp.

◆ outputOMPLPlanningYAML()

bool MoveItConfigData::outputOMPLPlanningYAML ( const std::string &  file_path)

Definition at line 266 of file moveit_config_data.cpp.

◆ outputROSControllersYAML()

bool MoveItConfigData::outputROSControllersYAML ( const std::string &  file_path)

Definition at line 1047 of file moveit_config_data.cpp.

◆ outputSetupAssistantFile()

bool MoveItConfigData::outputSetupAssistantFile ( const std::string &  file_path)

SRDF Path Location

Package generation time

Update the parsed setup_assistant timestamp

Definition at line 193 of file moveit_config_data.cpp.

◆ outputSimpleControllersYAML()

bool MoveItConfigData::outputSimpleControllersYAML ( const std::string &  file_path)

Definition at line 983 of file moveit_config_data.cpp.

◆ outputSTOMPPlanningYAML()

bool MoveItConfigData::outputSTOMPPlanningYAML ( const std::string &  file_path)

Definition at line 346 of file moveit_config_data.cpp.

◆ parseROSController()

bool MoveItConfigData::parseROSController ( const YAML::Node &  controller)

Helper function for parsing ros_controllers.yaml file

Parameters
YAML::Node- individual controller to be parsed
Returns
true if the file was read correctly

Definition at line 1515 of file moveit_config_data.cpp.

◆ processROSControllers()

bool MoveItConfigData::processROSControllers ( std::ifstream &  input_stream)

Helper function for parsing ros_controllers.yaml file

Parameters
std::ifstreamof ros_controller.yaml
Returns
true if the file was read correctly

Definition at line 1561 of file moveit_config_data.cpp.

◆ setPackagePath()

bool MoveItConfigData::setPackagePath ( const std::string &  pkg_path)

Set package path; try to resolve path from package name if directory does not exist

Parameters
pkg_pathpath to package or package name
Returns
true if the path was set

Definition at line 1676 of file moveit_config_data.cpp.

◆ setRobotModel()

void MoveItConfigData::setRobotModel ( const moveit::core::RobotModelPtr &  robot_model)

Load a robot model.

Definition at line 120 of file moveit_config_data.cpp.

◆ updateRobotModel()

void MoveItConfigData::updateRobotModel ( )

Update the Kinematic Model with latest SRDF modifications.

Definition at line 142 of file moveit_config_data.cpp.

Member Data Documentation

◆ allowed_collision_matrix_

collision_detection::AllowedCollisionMatrix moveit_setup_assistant::MoveItConfigData::allowed_collision_matrix_

Allowed collision matrix for robot poses.

Definition at line 306 of file moveit_config_data.h.

◆ author_email_

std::string moveit_setup_assistant::MoveItConfigData::author_email_

Email of the author of this config.

Definition at line 315 of file moveit_config_data.h.

◆ author_name_

std::string moveit_setup_assistant::MoveItConfigData::author_name_

Name of the author of this config.

Definition at line 312 of file moveit_config_data.h.

◆ changes

unsigned long moveit_setup_assistant::MoveItConfigData::changes

Definition at line 241 of file moveit_config_data.h.

◆ config_pkg_generated_timestamp_

std::time_t moveit_setup_assistant::MoveItConfigData::config_pkg_generated_timestamp_

Timestamp when configuration package was generated, if it was previously generated.

Definition at line 309 of file moveit_config_data.h.

◆ config_pkg_path_

std::string moveit_setup_assistant::MoveItConfigData::config_pkg_path_

Loaded configuration package path - if an existing package was loaded, holds that path.

Definition at line 297 of file moveit_config_data.h.

◆ controller_configs_

std::vector<ControllerConfig> moveit_setup_assistant::MoveItConfigData::controller_configs_
private

Controllers config data.

Definition at line 556 of file moveit_config_data.h.

◆ debug_

bool moveit_setup_assistant::MoveItConfigData::debug_

Is this application in debug mode?

Definition at line 303 of file moveit_config_data.h.

◆ gazebo_urdf_string_

std::string moveit_setup_assistant::MoveItConfigData::gazebo_urdf_string_

Gazebo URDF robot model string.

Definition at line 271 of file moveit_config_data.h.

◆ group_meta_data_

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 291 of file moveit_config_data.h.

◆ planning_scene_

planning_scene::PlanningScenePtr moveit_setup_assistant::MoveItConfigData::planning_scene_
private

Shared planning scene.

Definition at line 559 of file moveit_config_data.h.

◆ robot_model_

moveit::core::RobotModelPtr moveit_setup_assistant::MoveItConfigData::robot_model_
private

Shared kinematic model.

Definition at line 553 of file moveit_config_data.h.

◆ sensors_plugin_config_parameter_list_

std::vector<std::map<std::string, GenericParameter> > moveit_setup_assistant::MoveItConfigData::sensors_plugin_config_parameter_list_
private

Sensor plugin configuration parameter list, each sensor plugin type is a map.

Definition at line 550 of file moveit_config_data.h.

◆ setup_assistant_path_

std::string moveit_setup_assistant::MoveItConfigData::setup_assistant_path_

Setup Assistants package's path for when we use its templates.

Definition at line 294 of file moveit_config_data.h.

◆ srdf_

srdf::SRDFWriterPtr moveit_setup_assistant::MoveItConfigData::srdf_

SRDF Data and Writer.

Definition at line 284 of file moveit_config_data.h.

◆ srdf_path_

std::string moveit_setup_assistant::MoveItConfigData::srdf_path_

Full file-system path to srdf.

Definition at line 278 of file moveit_config_data.h.

◆ srdf_pkg_relative_path_

std::string moveit_setup_assistant::MoveItConfigData::srdf_pkg_relative_path_

Path relative to loaded configuration package.

Definition at line 281 of file moveit_config_data.h.

◆ template_package_path_

std::string moveit_setup_assistant::MoveItConfigData::template_package_path_

Location that moveit_setup_assistant stores its templates.

Definition at line 300 of file moveit_config_data.h.

◆ urdf_from_xacro_

bool moveit_setup_assistant::MoveItConfigData::urdf_from_xacro_

Flag indicating whether the URDF was loaded from .xacro format.

Definition at line 259 of file moveit_config_data.h.

◆ urdf_model_

urdf::ModelSharedPtr moveit_setup_assistant::MoveItConfigData::urdf_model_

URDF robot model.

Definition at line 264 of file moveit_config_data.h.

◆ urdf_path_

std::string moveit_setup_assistant::MoveItConfigData::urdf_path_

Full file-system path to urdf.

Definition at line 250 of file moveit_config_data.h.

◆ urdf_pkg_name_

std::string moveit_setup_assistant::MoveItConfigData::urdf_pkg_name_

Name of package containig urdf (note: this may be empty b/c user may not have urdf in pkg)

Definition at line 253 of file moveit_config_data.h.

◆ urdf_pkg_relative_path_

std::string moveit_setup_assistant::MoveItConfigData::urdf_pkg_relative_path_

Path relative to urdf package (note: this may be same as urdf_path_)

Definition at line 256 of file moveit_config_data.h.

◆ urdf_string_

std::string moveit_setup_assistant::MoveItConfigData::urdf_string_

URDF robot model string.

Definition at line 267 of file moveit_config_data.h.

◆ xacro_args_

std::string moveit_setup_assistant::MoveItConfigData::xacro_args_

xacro arguments

Definition at line 261 of file moveit_config_data.h.


The documentation for this class was generated from the following files:


moveit_setup_assistant
Author(s): Dave Coleman
autogenerated on Sat May 3 2025 02:28:05