Classes | Public Types | 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  joint_model_compare
 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,
  AUTHOR_INFO = 1 << 9, SENSORS_CONFIG = 1 << 10, SRDF = COLLISIONS | VIRTUAL_JOINTS | GROUPS | GROUP_CONTENTS | POSES | END_EFFECTORS | PASSIVE_JOINTS
}
 

Public Member Functions

bool addDefaultControllers ()
 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...
 
bool addROSController (const ROSControlConfig &new_controller)
 Adds a ROS controller to ros_controllers_config_ vector. 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 (std::string planning_group)
 Decide the best two joints to be used for the projection evaluator. More...
 
bool deleteROSController (const std::string &controller_name)
 
srdf::Model::GroupfindGroupByName (const std::string &name)
 
ROSControlConfigfindROSControllerByName (const std::string &controller_name)
 
std::string getGazeboCompatibleURDF ()
 Parses the existing urdf and constructs a string from it with the elements required by gazebo simulator added. More...
 
std::string getJointHardwareInterface (const std::string &joint_name)
 Helper function to get the controller that is controlling the joint. More...
 
std::vector< OMPLPlannerDescriptiongetOMPLPlanners ()
 
planning_scene::PlanningScenePtr getPlanningScene ()
 Provide a shared planning scene. More...
 
robot_model::RobotModelConstPtr getRobotModel ()
 Provide a shared kinematic model loader. More...
 
std::vector< ROSControlConfig > & getROSControllers ()
 Gets ros_controllers_config_ vector. More...
 
std::vector< std::map< std::string, GenericParameter > > getSensorPluginConfig ()
 Used for adding a sensor plugin configuation parameter to the sensor plugin configuration parameter list. More...
 
bool getSetupAssistantYAMLPath (std::string &path)
 
bool input3DSensorsYAML (const std::string &default_file_path, const std::string &file_path="")
 
bool inputKinematicsYAML (const std::string &file_path)
 
bool inputOMPLYAML (const std::string &file_path)
 
bool inputROSControllersYAML (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. More...
 
 MoveItConfigData ()
 
bool output3DSensorPluginYAML (const std::string &file_path)
 
bool outputCHOMPPlanningYAML (const std::string &file_path)
 
bool outputFakeControllersYAML (const std::string &file_path)
 
void outputFollowJointTrajectoryYAML (YAML::Emitter &emitter, std::vector< ROSControlConfig > &ros_controllers_config_output)
 
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 parseROSController (const YAML::Node &controller)
 
bool processROSControllers (std::ifstream &input_stream)
 
void setCollisionLinkPairs (const moveit_setup_assistant::LinkPairMap &link_pairs, size_t skip_mask=0)
 Set list of collision link pairs in SRDF; sorted; with optional filter. More...
 
bool setPackagePath (const std::string &pkg_path)
 
void setRobotModel (robot_model::RobotModelPtr robot_model)
 Load a robot model. More...
 
void updateRobotModel ()
 Update the Kinematic Model with latest SRDF modifications. More...
 
 ~MoveItConfigData ()
 

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

planning_scene::PlanningScenePtr planning_scene_
 Shared planning scene. More...
 
robot_model::RobotModelPtr robot_model_
 Shared kinematic model. More...
 
std::vector< ROSControlConfigros_controllers_config_
 ROS Controllers config data. 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 188 of file moveit_config_data.h.

Member Enumeration Documentation

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

Definition at line 195 of file moveit_config_data.h.

Constructor & Destructor Documentation

MoveItConfigData::MoveItConfigData ( )

Definition at line 56 of file moveit_config_data.cpp.

MoveItConfigData::~MoveItConfigData ( )

Definition at line 76 of file moveit_config_data.cpp.

Member Function Documentation

bool MoveItConfigData::addDefaultControllers ( )

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

Returns
true if controllers were added to the ros_controllers_config_ data structure

Definition at line 1429 of file moveit_config_data.cpp.

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 1808 of file moveit_config_data.cpp.

bool MoveItConfigData::addROSController ( const ROSControlConfig new_controller)

Adds a ROS controller to ros_controllers_config_ vector.

Parameters
new_controllera new ROS Controller to add
Returns
true if inserted correctly

Definition at line 1782 of file moveit_config_data.cpp.

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 1710 of file moveit_config_data.cpp.

void MoveItConfigData::clearSensorPluginConfig ( )

Clear the sensor plugin configuration parameter list.

Definition at line 1829 of file moveit_config_data.cpp.

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

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

Definition at line 1535 of file moveit_config_data.cpp.

bool MoveItConfigData::createFullURDFPath ( )

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

Definition at line 1503 of file moveit_config_data.cpp.

std::string MoveItConfigData::decideProjectionJoints ( 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 1166 of file moveit_config_data.cpp.

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

Delete ROS controller by name

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

Definition at line 1764 of file moveit_config_data.cpp.

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 1717 of file moveit_config_data.cpp.

ROSControlConfig * MoveItConfigData::findROSControllerByName ( const std::string &  controller_name)

Find the associated ROS controller by name

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

Definition at line 1743 of file moveit_config_data.cpp.

std::string MoveItConfigData::getGazeboCompatibleURDF ( )

Parses the existing urdf and constructs a string from it with the elements required by gazebo simulator added.

Returns
gazebo compatible urdf or empty if error encountered

Definition at line 404 of file moveit_config_data.cpp.

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 380 of file moveit_config_data.cpp.

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

Definition at line 553 of file moveit_config_data.cpp.

planning_scene::PlanningScenePtr MoveItConfigData::getPlanningScene ( )

Provide a shared planning scene.

Definition at line 122 of file moveit_config_data.cpp.

robot_model::RobotModelConstPtr MoveItConfigData::getRobotModel ( )

Provide a shared kinematic model loader.

Definition at line 91 of file moveit_config_data.cpp.

std::vector< ROSControlConfig > & MoveItConfigData::getROSControllers ( )

Gets ros_controllers_config_ vector.

Returns
pointer to ros_controllers_config_

Definition at line 1800 of file moveit_config_data.cpp.

std::vector< std::map< std::string, GenericParameter > > MoveItConfigData::getSensorPluginConfig ( )

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

Definition at line 1821 of file moveit_config_data.cpp.

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 1492 of file moveit_config_data.cpp.

bool MoveItConfigData::input3DSensorsYAML ( const std::string &  default_file_path,
const std::string &  file_path = "" 
)

Input sensors_3d file - contains 3d sensors config data

Parameters
default_file_pathpath to sensors_3d yaml file which contains default parameter values
file_pathpath to sensors_3d yaml file in the config package
Returns
true if the file was read correctly

Definition at line 1601 of file moveit_config_data.cpp.

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 1254 of file moveit_config_data.cpp.

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 1206 of file moveit_config_data.cpp.

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 1402 of file moveit_config_data.cpp.

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 1545 of file moveit_config_data.cpp.

void MoveItConfigData::loadAllowedCollisionMatrix ( )

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

Definition at line 138 of file moveit_config_data.cpp.

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

Definition at line 979 of file moveit_config_data.cpp.

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

Definition at line 285 of file moveit_config_data.cpp.

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

Definition at line 506 of file moveit_config_data.cpp.

void MoveItConfigData::outputFollowJointTrajectoryYAML ( YAML::Emitter &  emitter,
std::vector< ROSControlConfig > &  ros_controllers_config_output 
)

Helper function for writing follow joint trajectory ROS controllers to ros_controllers.yaml

Parameters
YAMLEmitter - yaml emitter used to write the config to the ROS controllers yaml file
vector<ROSControlConfig>- a copy of ROS controllers config which will be modified in the function

Definition at line 743 of file moveit_config_data.cpp.

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

Definition at line 1023 of file moveit_config_data.cpp.

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

Definition at line 326 of file moveit_config_data.cpp.

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

Definition at line 204 of file moveit_config_data.cpp.

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

Definition at line 802 of file moveit_config_data.cpp.

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

SRDF Path Location

Package generation time

Definition at line 154 of file moveit_config_data.cpp.

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 1300 of file moveit_config_data.cpp.

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 1346 of file moveit_config_data.cpp.

void MoveItConfigData::setCollisionLinkPairs ( const moveit_setup_assistant::LinkPairMap link_pairs,
size_t  skip_mask = 0 
)

Set list of collision link pairs in SRDF; sorted; with optional filter.

Parameters
link_pairslist of collision link pairs
skip_maskmask of shifted moveit_setup_assistant::DisabledReason values that will be skipped

Definition at line 1134 of file moveit_config_data.cpp.

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 1462 of file moveit_config_data.cpp.

void MoveItConfigData::setRobotModel ( robot_model::RobotModelPtr  robot_model)

Load a robot model.

Definition at line 83 of file moveit_config_data.cpp.

void MoveItConfigData::updateRobotModel ( )

Update the Kinematic Model with latest SRDF modifications.

Definition at line 105 of file moveit_config_data.cpp.

Member Data Documentation

collision_detection::AllowedCollisionMatrix moveit_setup_assistant::MoveItConfigData::allowed_collision_matrix_

Allowed collision matrix for robot poses.

Definition at line 270 of file moveit_config_data.h.

std::string moveit_setup_assistant::MoveItConfigData::author_email_

Email of the author of this config.

Definition at line 279 of file moveit_config_data.h.

std::string moveit_setup_assistant::MoveItConfigData::author_name_

Name of the author of this config.

Definition at line 276 of file moveit_config_data.h.

unsigned long moveit_setup_assistant::MoveItConfigData::changes

Definition at line 209 of file moveit_config_data.h.

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

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

bool moveit_setup_assistant::MoveItConfigData::debug_

Is this application in debug mode?

Definition at line 267 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 255 of file moveit_config_data.h.

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

Shared planning scene.

Definition at line 519 of file moveit_config_data.h.

robot_model::RobotModelPtr moveit_setup_assistant::MoveItConfigData::robot_model_
private

Shared kinematic model.

Definition at line 513 of file moveit_config_data.h.

std::vector<ROSControlConfig> moveit_setup_assistant::MoveItConfigData::ros_controllers_config_
private

ROS Controllers config data.

Definition at line 516 of file moveit_config_data.h.

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

std::string moveit_setup_assistant::MoveItConfigData::setup_assistant_path_

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

Definition at line 258 of file moveit_config_data.h.

srdf::SRDFWriterPtr moveit_setup_assistant::MoveItConfigData::srdf_

SRDF Data and Writer.

Definition at line 248 of file moveit_config_data.h.

std::string moveit_setup_assistant::MoveItConfigData::srdf_path_

Full file-system path to srdf.

Definition at line 242 of file moveit_config_data.h.

std::string moveit_setup_assistant::MoveItConfigData::srdf_pkg_relative_path_

Path relative to loaded configuration package.

Definition at line 245 of file moveit_config_data.h.

std::string moveit_setup_assistant::MoveItConfigData::template_package_path_

Location that moveit_setup_assistant stores its templates.

Definition at line 264 of file moveit_config_data.h.

bool moveit_setup_assistant::MoveItConfigData::urdf_from_xacro_

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

Definition at line 227 of file moveit_config_data.h.

urdf::ModelSharedPtr moveit_setup_assistant::MoveItConfigData::urdf_model_

URDF robot model.

Definition at line 232 of file moveit_config_data.h.

std::string moveit_setup_assistant::MoveItConfigData::urdf_path_

Full file-system path to urdf.

Definition at line 218 of file moveit_config_data.h.

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

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

std::string moveit_setup_assistant::MoveItConfigData::urdf_string_

URDF robot model string.

Definition at line 235 of file moveit_config_data.h.

std::string moveit_setup_assistant::MoveItConfigData::xacro_args_

xacro arguments

Definition at line 229 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 Wed Jul 10 2019 04:04:34