37 #ifndef MOVEIT_MOVEIT_SETUP_ASSISTANT_TOOLS_MOVEIT_CONFIG_DATA_ 38 #define MOVEIT_MOVEIT_SETUP_ASSISTANT_TOOLS_MOVEIT_CONFIG_DATA_ 40 #include <boost/shared_ptr.hpp> 44 #include <yaml-cpp/yaml.h> 118 parameter_list_.clear();
125 void addParameter(
const std::string& name,
const std::string& value =
"",
const std::string& comment =
"")
131 parameter_list_.push_back(temp);
198 VIRTUAL_JOINTS = 1 << 2,
200 GROUP_CONTENTS = 1 << 4,
201 GROUP_KINEMATICS = 1 << 5,
203 END_EFFECTORS = 1 << 7,
204 PASSIVE_JOINTS = 1 << 8,
205 AUTHOR_INFO = 1 << 9,
206 SENSORS_CONFIG = 1 << 10,
207 SRDF = COLLISIONS | VIRTUAL_JOINTS | GROUPS | GROUP_CONTENTS | POSES | END_EFFECTORS | PASSIVE_JOINTS
286 void setRobotModel(robot_model::RobotModelPtr robot_model);
289 robot_model::RobotModelConstPtr getRobotModel();
292 void updateRobotModel();
295 planning_scene::PlanningScenePtr getPlanningScene();
306 void loadAllowedCollisionMatrix();
311 std::vector<OMPLPlannerDescription> getOMPLPlanners();
312 bool outputSetupAssistantFile(
const std::string& file_path);
313 bool outputOMPLPlanningYAML(
const std::string& file_path);
314 bool outputCHOMPPlanningYAML(
const std::string& file_path);
315 bool outputKinematicsYAML(
const std::string& file_path);
316 bool outputJointLimitsYAML(
const std::string& file_path);
317 bool outputFakeControllersYAML(
const std::string& file_path);
324 void outputFollowJointTrajectoryYAML(YAML::Emitter& emitter,
325 std::vector<ROSControlConfig>& ros_controllers_config_output);
327 bool outputROSControllersYAML(
const std::string& file_path);
328 bool output3DSensorPluginYAML(
const std::string& file_path);
334 std::string getJointHardwareInterface(
const std::string& joint_name);
341 std::string getGazeboCompatibleURDF();
355 std::string decideProjectionJoints(std::string planning_group);
362 bool inputOMPLYAML(
const std::string& file_path);
369 bool inputKinematicsYAML(
const std::string& file_path);
376 bool parseROSController(
const YAML::Node& controller);
383 bool processROSControllers(std::ifstream& input_stream);
390 bool inputROSControllersYAML(
const std::string& file_path);
396 bool addDefaultControllers();
403 bool setPackagePath(
const std::string& pkg_path);
410 bool getSetupAssistantYAMLPath(std::string& path);
413 bool createFullURDFPath();
416 bool createFullSRDFPath(
const std::string& package_path);
424 bool inputSetupAssistantYAML(
const std::string& file_path);
433 bool input3DSensorsYAML(
const std::string& default_file_path,
const std::string& file_path =
"");
443 std::string appendPaths(
const std::string& path1,
const std::string& path2);
456 std::vector<ROSControlConfig>& getROSControllers();
464 ROSControlConfig* findROSControllerByName(
const std::string& controller_name);
472 bool deleteROSController(
const std::string& controller_name);
477 void addGenericParameterToSensorPluginConfig(
const std::string& name,
const std::string& value =
"",
478 const std::string& comment =
"");
483 void clearSensorPluginConfig();
488 std::vector<std::map<std::string, GenericParameter> > getSensorPluginConfig();
493 std::string getDefaultStartStateGroup();
498 std::string getDefaultStartPose();
508 bool operator()(
const robot_model::JointModel* jm1,
const robot_model::JointModel* jm2)
const 510 return jm1->getName() < jm2->getName();
std::time_t config_pkg_generated_timestamp_
Timestamp when configuration package was generated, if it was previously generated.
~OMPLPlannerDescription()
Destructor.
std::string urdf_pkg_relative_path_
Path relative to urdf package (note: this may be same as urdf_path_)
static const int DEFAULT_KIN_SOLVER_ATTEMPTS_
std::string srdf_pkg_relative_path_
Path relative to loaded configuration package.
std::vector< OmplPlanningParameter > parameter_list_
robot_model::RobotModelPtr robot_model_
Shared kinematic model.
urdf::ModelSharedPtr urdf_model_
URDF robot model.
std::vector< std::string > joints_
static const double DEFAULT_KIN_SOLVER_TIMEOUT_
std::vector< ROSControlConfig > ros_controllers_config_
ROS Controllers config data.
srdf::SRDFWriterPtr srdf_
SRDF Data and Writer.
std::string author_name_
Name of the author of this config.
std::map< std::string, GroupMetaData > group_meta_data_
Planning groups extra data not found in srdf but used in config files.
static const std::string MOVEIT_ROBOT_STATE
MOVEIT_CLASS_FORWARD(MoveItConfigData)
std::string setup_assistant_path_
Setup Assistants package's path for when we use its templates.
static const double DEFAULT_KIN_SOLVER_SEARCH_RESOLUTION_
std::string urdf_string_
URDF robot model string.
void setValue(std::string value)
This class describes the OMPL planners by name, type, and parameter list, used to create the ompl_pla...
std::string srdf_path_
Full file-system path to srdf.
bool operator()(const robot_model::JointModel *jm1, const robot_model::JointModel *jm2) const
std::string author_email_
Email of the author of this config.
bool urdf_from_xacro_
Flag indicating whether the URDF was loaded from .xacro format.
OMPLPlannerDescription(const std::string &name, const std::string &type)
Constructor.
This class is shared with all widgets and contains the common configuration data needed for generatin...
std::string xacro_args_
xacro arguments
static const std::string ROBOT_DESCRIPTION
bool debug_
Is this application in debug mode?
Custom std::set comparator, used for sorting the joint_limits.yaml file into alphabetical order...
std::string urdf_pkg_name_
Name of package containig urdf (note: this may be empty b/c user may not have urdf in pkg) ...
void setComment(std::string comment)
std::string urdf_path_
Full file-system path to urdf.
collision_detection::AllowedCollisionMatrix allowed_collision_matrix_
Allowed collision matrix for robot poses.
void addParameter(const std::string &name, const std::string &value="", const std::string &comment="")
adds a parameter to the planner description
std::string template_package_path_
Location that moveit_setup_assistant stores its templates.
void setName(std::string name)
std::string config_pkg_path_
Loaded configuration package path - if an existing package was loaded, holds that path...
std::vector< std::map< std::string, GenericParameter > > sensors_plugin_config_parameter_list_
Sensor plugin configuration parameter list, each sensor plugin type is a map.
std::map< std::pair< std::string, std::string >, LinkPairData > LinkPairMap
LinkPairMap is an adjacency list structure containing links in string-based form. Used for disabled l...
planning_scene::PlanningScenePtr planning_scene_
Shared planning scene.