Go to the documentation of this file.
41 #include <yaml-cpp/yaml.h>
83 struct ControllerConfig
93 struct OmplPlanningParameter
124 void addParameter(
const std::string& name,
const std::string& value =
"",
const std::string& comment =
"")
154 value_ = std::move(value);
160 const std::string&
getName()
const
290 void setRobotModel(
const moveit::core::RobotModelPtr& robot_model);
387 bool addDefaultControllers(
const std::string& controller_type =
"effort_controllers/JointTrajectoryController");
404 std::string& relative_filepath)
const;
430 static std::vector<std::map<std::string, GenericParameter>>
load3DSensorsYAML(
const std::string& file_path);
440 std::string
appendPaths(
const std::string& path1,
const std::string& path2);
478 const std::string& comment =
"");
504 struct JointModelCompare
bool setPackagePath(const std::string &pkg_path)
static const std::string ROBOT_DESCRIPTION
std::string srdf_path_
Full file-system path to srdf.
bool inputOMPLYAML(const std::string &file_path)
void input3DSensorsYAML(const std::string &file_path)
Load perception sensor config (sensors_3d.yaml) into internal data structure.
bool deleteController(const std::string &controller_name)
const std::string & getValue() const
bool createFullSRDFPath(const std::string &package_path)
Make the full SRDF path using the loaded .setup_assistant data.
const std::vector< std::map< std::string, GenericParameter > > & getSensorPluginConfig() const
Used for adding a sensor plugin configuation parameter to the sensor plugin configuration parameter l...
const std::string & getName() const
bool inputKinematicsYAML(const std::string &file_path)
void loadAllowedCollisionMatrix(const srdf::SRDFWriter &srdf)
Load the allowed collision matrix from the SRDF's list of link pairs.
void clearSensorPluginConfig()
Clear the sensor plugin configuration parameter list.
moveit::core::RobotModelPtr robot_model_
Shared kinematic model.
void addParameter(const std::string &name, const std::string &value="", const std::string &comment="")
adds a parameter to the planner description
void setComment(std::string comment)
std::string decideProjectionJoints(const std::string &planning_group)
Decide the best two joints to be used for the projection evaluator.
bool outputOMPLPlanningYAML(const std::string &file_path)
const std::string & getName() const
bool inputSetupAssistantYAML(const std::string &file_path)
std::string template_package_path_
Location that moveit_setup_assistant stores its templates.
bool addDefaultControllers(const std::string &controller_type="effort_controllers/JointTrajectoryController")
Add a Follow Joint Trajectory action Controller for each Planning Group.
static const std::string MOVEIT_ROBOT_STATE
std::vector< OmplPlanningParameter > parameter_list_
std::map< std::string, GroupMetaData > group_meta_data_
Planning groups extra data not found in srdf but used in config files.
std::string urdf_pkg_relative_path_
Path relative to urdf package (note: this may be same as urdf_path_)
std::string gazebo_urdf_string_
Gazebo URDF robot model string.
std::vector< std::map< std::string, GenericParameter > > sensors_plugin_config_parameter_list_
Sensor plugin configuration parameter list, each sensor plugin type is a map.
bool outputJointLimitsYAML(const std::string &file_path)
bool addController(const ControllerConfig &new_controller)
Adds a controller to controller_configs_ vector.
std::string author_email_
Email of the author of this config.
bool extractPackageNameFromPath(const std::string &path, std::string &package_name, std::string &relative_filepath) const
~OMPLPlannerDescription()
Destructor.
std::vector< OMPLPlannerDescription > getOMPLPlanners() const
This class is shared with all widgets and contains the common configuration data needed for generatin...
bool outputSimpleControllersYAML(const std::string &file_path)
void setValue(std::string value)
std::string setup_assistant_path_
Setup Assistants package's path for when we use its templates.
OMPLPlannerDescription(const std::string &name, const std::string &type)
Constructor.
planning_scene::PlanningScenePtr getPlanningScene()
Provide a shared planning scene.
bool outputSetupAssistantFile(const std::string &file_path)
bool parseROSController(const YAML::Node &controller)
bool getSetupAssistantYAMLPath(std::string &path)
moveit::core::RobotModelConstPtr getRobotModel()
Provide a shared kinematic model loader.
bool outputROSControllersYAML(const std::string &file_path)
bool urdf_from_xacro_
Flag indicating whether the URDF was loaded from .xacro format.
std::string urdf_string_
URDF robot model string.
srdf::SRDFWriterPtr srdf_
SRDF Data and Writer.
void updateRobotModel()
Update the Kinematic Model with latest SRDF modifications.
std::string author_name_
Name of the author of this config.
std::vector< ControllerConfig > & getControllers()
Gets controller_configs_ vector.
bool debug_
Is this application in debug mode?
bool createFullURDFPath()
Make the full URDF path using the loaded .setup_assistant data.
std::string appendPaths(const std::string &path1, const std::string &path2)
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 li...
static std::vector< std::map< std::string, GenericParameter > > load3DSensorsYAML(const std::string &file_path)
Load perception sensor config.
std::string getJointHardwareInterface(const std::string &joint_name)
Helper function to get the controller that is controlling the joint.
bool inputROSControllersYAML(const std::string &file_path)
std::map< std::string, double > getInitialJoints() const
bool outputSTOMPPlanningYAML(const std::string &file_path)
void setName(std::string name)
collision_detection::AllowedCollisionMatrix allowed_collision_matrix_
Allowed collision matrix for robot poses.
srdf::Model::Group * findGroupByName(const std::string &name)
std::string config_pkg_path_
Loaded configuration package path - if an existing package was loaded, holds that path.
static const double DEFAULT_KIN_SOLVER_TIMEOUT
urdf::ModelSharedPtr urdf_model_
URDF robot model.
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 xacro_args_
xacro arguments
std::vector< ControllerConfig > controller_configs_
Controllers config data.
planning_scene::PlanningScenePtr planning_scene_
Shared planning scene.
bool operator()(const moveit::core::JointModel *jm1, const moveit::core::JointModel *jm2) const
srdf::Model::GroupState getDefaultStartPose()
Helper function to get the default start pose for moveit_sim_hw_interface.
std::string srdf_pkg_relative_path_
Path relative to loaded configuration package.
std::vector< std::string > joints_
ControllerConfig * findControllerByName(const std::string &controller_name)
bool processROSControllers(std::ifstream &input_stream)
const std::string & getComment() const
bool outputKinematicsYAML(const std::string &file_path)
std::time_t config_pkg_generated_timestamp_
Timestamp when configuration package was generated, if it was previously generated.
bool output3DSensorPluginYAML(const std::string &file_path)
This class describes the OMPL planners by name, type, and parameter list, used to create the ompl_pla...
void setRobotModel(const moveit::core::RobotModelPtr &robot_model)
Load a robot model.
std::string urdf_path_
Full file-system path to urdf.
bool inputPlanningContextLaunch(const std::string &file_path)
bool outputFakeControllersYAML(const std::string &file_path)
MOVEIT_CLASS_FORWARD(MoveItConfigData)
static const double DEFAULT_KIN_SOLVER_SEARCH_RESOLUTION
bool outputGazeboURDFFile(const std::string &file_path)
std::shared_ptr< SRDFWriter > SRDFWriterPtr