moveit_config_data.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Dave Coleman */
36 
37 #pragma once
38 
40 #include <moveit/planning_scene/planning_scene.h> // for getting kinematic model
41 #include <yaml-cpp/yaml.h> // outputing yaml config files
42 #include <urdf/model.h> // to share throughout app
43 #include <srdfdom/srdf_writer.h> // for writing srdf data
44 
45 #include <utility>
46 
47 namespace moveit_setup_assistant
48 {
49 // ******************************************************************************************
50 // Constants
51 // ******************************************************************************************
52 
53 // Used for loading kinematic model
54 static const std::string ROBOT_DESCRIPTION = "robot_description";
55 static const std::string MOVEIT_ROBOT_STATE = "moveit_robot_state";
56 
57 // Default kin solver values
58 static const double DEFAULT_KIN_SOLVER_SEARCH_RESOLUTION = 0.005;
59 static const double DEFAULT_KIN_SOLVER_TIMEOUT = 0.005;
60 
61 // ******************************************************************************************
62 // Structs
63 // ******************************************************************************************
64 
68 struct GroupMetaData
69 {
70  std::string kinematics_solver_; // Name of kinematics plugin to use
71  double kinematics_solver_search_resolution_; // resolution to use with solver
72  double kinematics_solver_timeout_; // solver timeout
73  double goal_joint_tolerance_; // joint tolerance for goal constraints
74  double goal_position_tolerance_; // position tolerance for goal constraints
75  double goal_orientation_tolerance_; // orientation tolerance for goal constraints
76  std::string kinematics_parameters_file_; // file for additional kinematics parameters
77  std::string default_planner_; // Name of the default planner to use
78 };
79 
83 struct ControllerConfig
84 {
85  std::string name_; // controller name
86  std::string type_; // controller type
87  std::vector<std::string> joints_; // joints controller by this controller
88 };
89 
93 struct OmplPlanningParameter
94 {
95  std::string name; // name of parameter
96  std::string value; // value parameter will receive (but as a string)
97  std::string comment; // comment briefly describing what this parameter does
98 };
99 
103 {
104 public:
109  OMPLPlannerDescription(const std::string& name, const std::string& type)
110  {
111  name_ = name;
112  type_ = type;
113  };
116  {
118  };
124  void addParameter(const std::string& name, const std::string& value = "", const std::string& comment = "")
125  {
127  temp.name = name;
128  temp.value = value;
129  temp.comment = comment;
130  parameter_list_.push_back(temp);
131  }
132  std::vector<OmplPlanningParameter> parameter_list_;
133  std::string name_; // name of planner
134  std::string type_; // type of planner (geometric)
135 };
136 
140 class GenericParameter
141 {
142 public:
144  {
145  comment_ = "";
146  };
147 
148  void setName(std::string name)
149  {
150  name_ = std::move(name);
151  };
152  void setValue(std::string value)
153  {
154  value_ = std::move(value);
155  };
156  void setComment(std::string comment)
157  {
158  comment_ = std::move(comment);
159  };
160  const std::string& getName() const
161  {
162  return name_;
163  };
164  const std::string& getValue() const
165  {
166  return value_;
167  };
168  const std::string& getComment() const
169  {
170  return comment_;
171  };
172 
173 private:
174  std::string name_; // name of parameter
175  std::string value_; // value parameter will receive (but as a string)
176  std::string comment_; // comment briefly describing what this parameter does
177 };
178 
179 MOVEIT_CLASS_FORWARD(MoveItConfigData); // Defines MoveItConfigDataPtr, ConstPtr, WeakPtr... etc
180 
187 class MoveItConfigData
188 {
189 public:
192 
193  // bits of information that can be entered in Setup Assistant
194  enum InformationFields
195  {
196  COLLISIONS = 1 << 1,
197  VIRTUAL_JOINTS = 1 << 2,
198  GROUPS = 1 << 3,
199  GROUP_CONTENTS = 1 << 4,
201  POSES = 1 << 6,
202  END_EFFECTORS = 1 << 7,
203  PASSIVE_JOINTS = 1 << 8,
204  SIMULATION = 1 << 9,
205  AUTHOR_INFO = 1 << 10,
206  SENSORS_CONFIG = 1 << 11,
208  };
209  unsigned long changes; // bitfield of changes (composed of InformationFields)
210 
211  // All of the data needed for creating a MoveIt Configuration Files
212 
213  // ******************************************************************************************
214  // URDF Data
215  // ******************************************************************************************
216 
218  std::string urdf_path_;
219 
221  std::string urdf_pkg_name_;
222 
224  std::string urdf_pkg_relative_path_;
225 
227  bool urdf_from_xacro_;
229  std::string xacro_args_;
230 
232  urdf::ModelSharedPtr urdf_model_;
233 
235  std::string urdf_string_;
236 
238  // NOTE: Created when the robot urdf is not compatible with Gazebo.
239  std::string gazebo_urdf_string_;
240 
241  // ******************************************************************************************
242  // SRDF Data
243  // ******************************************************************************************
244 
246  std::string srdf_path_;
247 
249  std::string srdf_pkg_relative_path_;
250 
253 
254  // ******************************************************************************************
255  // Other Data
256  // ******************************************************************************************
257 
259  std::map<std::string, GroupMetaData> group_meta_data_;
260 
262  std::string setup_assistant_path_;
263 
265  std::string config_pkg_path_;
266 
268  std::string template_package_path_;
269 
271  bool debug_;
272 
275 
278 
280  std::string author_name_;
281 
283  std::string author_email_;
284 
285  // ******************************************************************************************
286  // Public Functions
287  // ******************************************************************************************
288 
290  void setRobotModel(const moveit::core::RobotModelPtr& robot_model);
291 
293  moveit::core::RobotModelConstPtr getRobotModel();
294 
296  void updateRobotModel();
297 
299  planning_scene::PlanningScenePtr getPlanningScene();
300 
307  srdf::Model::Group* findGroupByName(const std::string& name);
308 
311 
312  // ******************************************************************************************
313  // Public Functions for outputting configuration and setting files
314  // ******************************************************************************************
315  std::vector<OMPLPlannerDescription> getOMPLPlanners() const;
316  std::map<std::string, double> getInitialJoints() const;
317  bool outputSetupAssistantFile(const std::string& file_path);
318  bool outputGazeboURDFFile(const std::string& file_path);
319  bool outputOMPLPlanningYAML(const std::string& file_path);
320  bool outputSTOMPPlanningYAML(const std::string& file_path);
321  bool outputKinematicsYAML(const std::string& file_path);
322  bool outputJointLimitsYAML(const std::string& file_path);
323  bool outputFakeControllersYAML(const std::string& file_path);
324  bool outputSimpleControllersYAML(const std::string& file_path);
325  bool outputROSControllersYAML(const std::string& file_path);
326  bool output3DSensorPluginYAML(const std::string& file_path);
327 
332  std::string getJointHardwareInterface(const std::string& joint_name);
333 
339  std::string decideProjectionJoints(const std::string& planning_group);
340 
346  bool inputOMPLYAML(const std::string& file_path);
347 
353  bool inputKinematicsYAML(const std::string& file_path);
354 
360  bool inputPlanningContextLaunch(const std::string& file_path);
361 
367  bool parseROSController(const YAML::Node& controller);
368 
374  bool processROSControllers(std::ifstream& input_stream);
375 
381  bool inputROSControllersYAML(const std::string& file_path);
382 
387  bool addDefaultControllers(const std::string& controller_type = "effort_controllers/JointTrajectoryController");
388 
394  bool setPackagePath(const std::string& pkg_path);
395 
403  bool extractPackageNameFromPath(const std::string& path, std::string& package_name,
404  std::string& relative_filepath) const;
405 
411  bool getSetupAssistantYAMLPath(std::string& path);
412 
414  bool createFullURDFPath();
415 
417  bool createFullSRDFPath(const std::string& package_path);
418 
425  bool inputSetupAssistantYAML(const std::string& file_path);
426 
428  void input3DSensorsYAML(const std::string& file_path);
430  static std::vector<std::map<std::string, GenericParameter>> load3DSensorsYAML(const std::string& file_path);
431 
440  std::string appendPaths(const std::string& path1, const std::string& path2);
441 
447  bool addController(const ControllerConfig& new_controller);
448 
453  std::vector<ControllerConfig>& getControllers()
454  {
455  return controller_configs_;
456  }
457 
464  ControllerConfig* findControllerByName(const std::string& controller_name);
465 
472  bool deleteController(const std::string& controller_name);
473 
477  void addGenericParameterToSensorPluginConfig(const std::string& name, const std::string& value = "",
478  const std::string& comment = "");
479 
484 
488  const std::vector<std::map<std::string, GenericParameter>>& getSensorPluginConfig() const
489  {
491  }
492 
497 
504  struct JointModelCompare
505  {
506  bool operator()(const moveit::core::JointModel* jm1, const moveit::core::JointModel* jm2) const
507  {
508  return jm1->getName() < jm2->getName();
509  }
510  };
511 
512 private:
513  // ******************************************************************************************
514  // Private Vars
515  // ******************************************************************************************
516 
518  std::vector<std::map<std::string, GenericParameter>> sensors_plugin_config_parameter_list_;
519 
521  moveit::core::RobotModelPtr robot_model_;
522 
524  std::vector<ControllerConfig> controller_configs_;
525 
527  planning_scene::PlanningScenePtr planning_scene_;
528 };
529 
530 } // namespace moveit_setup_assistant
moveit_setup_assistant::MoveItConfigData::setPackagePath
bool setPackagePath(const std::string &pkg_path)
Definition: moveit_config_data.cpp:1676
moveit_setup_assistant::ROBOT_DESCRIPTION
static const std::string ROBOT_DESCRIPTION
Definition: moveit_config_data.h:86
moveit_setup_assistant::MoveItConfigData::PASSIVE_JOINTS
@ PASSIVE_JOINTS
Definition: moveit_config_data.h:235
moveit_setup_assistant::MoveItConfigData::srdf_path_
std::string srdf_path_
Full file-system path to srdf.
Definition: moveit_config_data.h:278
moveit_setup_assistant::MoveItConfigData::inputOMPLYAML
bool inputOMPLYAML(const std::string &file_path)
Definition: moveit_config_data.cpp:1375
moveit_setup_assistant::MoveItConfigData::input3DSensorsYAML
void input3DSensorsYAML(const std::string &file_path)
Load perception sensor config (sensors_3d.yaml) into internal data structure.
Definition: moveit_config_data.cpp:1855
moveit_setup_assistant::MoveItConfigData::deleteController
bool deleteController(const std::string &controller_name)
Definition: moveit_config_data.cpp:1969
moveit_setup_assistant::MoveItConfigData::AUTHOR_INFO
@ AUTHOR_INFO
Definition: moveit_config_data.h:237
moveit_setup_assistant::MoveItConfigData::SENSORS_CONFIG
@ SENSORS_CONFIG
Definition: moveit_config_data.h:238
moveit_setup_assistant::GenericParameter::getValue
const std::string & getValue() const
Definition: moveit_config_data.h:196
moveit_setup_assistant::MoveItConfigData::createFullSRDFPath
bool createFullSRDFPath(const std::string &package_path)
Make the full SRDF path using the loaded .setup_assistant data.
Definition: moveit_config_data.cpp:1789
moveit_setup_assistant::MoveItConfigData::getSensorPluginConfig
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...
Definition: moveit_config_data.h:520
moveit_setup_assistant::GenericParameter::getName
const std::string & getName() const
Definition: moveit_config_data.h:192
moveit_setup_assistant::GenericParameter::value_
std::string value_
Definition: moveit_config_data.h:207
moveit_setup_assistant::MoveItConfigData::inputKinematicsYAML
bool inputKinematicsYAML(const std::string &file_path)
Definition: moveit_config_data.cpp:1423
moveit_setup_assistant::MoveItConfigData::InformationFields
InformationFields
Definition: moveit_config_data.h:226
moveit_setup_assistant::OMPLPlannerDescription::name_
std::string name_
Definition: moveit_config_data.h:165
moveit_setup_assistant::MoveItConfigData::loadAllowedCollisionMatrix
void loadAllowedCollisionMatrix(const srdf::SRDFWriter &srdf)
Load the allowed collision matrix from the SRDF's list of link pairs.
Definition: moveit_config_data.cpp:175
moveit_setup_assistant::MoveItConfigData::clearSensorPluginConfig
void clearSensorPluginConfig()
Clear the sensor plugin configuration parameter list.
Definition: moveit_config_data.cpp:2016
moveit_setup_assistant::MoveItConfigData::robot_model_
moveit::core::RobotModelPtr robot_model_
Shared kinematic model.
Definition: moveit_config_data.h:553
srdf::SRDFWriter
moveit_setup_assistant::MoveItConfigData::MoveItConfigData
MoveItConfigData()
Definition: moveit_config_data.cpp:95
moveit_setup_assistant::OmplPlanningParameter::value
std::string value
Definition: moveit_config_data.h:128
moveit_setup_assistant::OMPLPlannerDescription::addParameter
void addParameter(const std::string &name, const std::string &value="", const std::string &comment="")
adds a parameter to the planner description
Definition: moveit_config_data.h:156
moveit_setup_assistant::GenericParameter::setComment
void setComment(std::string comment)
Definition: moveit_config_data.h:188
moveit_setup_assistant::MoveItConfigData::decideProjectionJoints
std::string decideProjectionJoints(const std::string &planning_group)
Decide the best two joints to be used for the projection evaluator.
Definition: moveit_config_data.cpp:1335
moveit_setup_assistant::MoveItConfigData::POSES
@ POSES
Definition: moveit_config_data.h:233
moveit_setup_assistant::MoveItConfigData::outputOMPLPlanningYAML
bool outputOMPLPlanningYAML(const std::string &file_path)
Definition: moveit_config_data.cpp:266
moveit::core::JointModel::getName
const std::string & getName() const
moveit_setup_assistant::MoveItConfigData::inputSetupAssistantYAML
bool inputSetupAssistantYAML(const std::string &file_path)
Definition: moveit_config_data.cpp:1799
moveit_setup_assistant::MoveItConfigData::template_package_path_
std::string template_package_path_
Location that moveit_setup_assistant stores its templates.
Definition: moveit_config_data.h:300
moveit_setup_assistant::MoveItConfigData::addDefaultControllers
bool addDefaultControllers(const std::string &controller_type="effort_controllers/JointTrajectoryController")
Add a Follow Joint Trajectory action Controller for each Planning Group.
Definition: moveit_config_data.cpp:1644
moveit_setup_assistant::OMPLPlannerDescription::type_
std::string type_
Definition: moveit_config_data.h:166
moveit_setup_assistant::MOVEIT_ROBOT_STATE
static const std::string MOVEIT_ROBOT_STATE
Definition: moveit_config_data.h:87
moveit_setup_assistant::OMPLPlannerDescription::parameter_list_
std::vector< OmplPlanningParameter > parameter_list_
Definition: moveit_config_data.h:164
moveit_setup_assistant::MoveItConfigData::group_meta_data_
std::map< std::string, GroupMetaData > group_meta_data_
Planning groups extra data not found in srdf but used in config files.
Definition: moveit_config_data.h:291
moveit_setup_assistant::MoveItConfigData::COLLISIONS
@ COLLISIONS
Definition: moveit_config_data.h:228
moveit_setup_assistant::MoveItConfigData::urdf_pkg_relative_path_
std::string urdf_pkg_relative_path_
Path relative to urdf package (note: this may be same as urdf_path_)
Definition: moveit_config_data.h:256
moveit_setup_assistant::MoveItConfigData::gazebo_urdf_string_
std::string gazebo_urdf_string_
Gazebo URDF robot model string.
Definition: moveit_config_data.h:271
moveit_setup_assistant::MoveItConfigData::sensors_plugin_config_parameter_list_
std::vector< std::map< std::string, GenericParameter > > sensors_plugin_config_parameter_list_
Sensor plugin configuration parameter list, each sensor plugin type is a map.
Definition: moveit_config_data.h:550
moveit_setup_assistant::MoveItConfigData::outputJointLimitsYAML
bool outputJointLimitsYAML(const std::string &file_path)
Definition: moveit_config_data.cpp:1238
moveit_setup_assistant::MoveItConfigData::addController
bool addController(const ControllerConfig &new_controller)
Adds a controller to controller_configs_ vector.
Definition: moveit_config_data.cpp:1987
moveit_setup_assistant::MoveItConfigData::author_email_
std::string author_email_
Email of the author of this config.
Definition: moveit_config_data.h:315
moveit_setup_assistant::MoveItConfigData::extractPackageNameFromPath
bool extractPackageNameFromPath(const std::string &path, std::string &package_name, std::string &relative_filepath) const
Definition: moveit_config_data.cpp:1707
moveit_setup_assistant::OMPLPlannerDescription::~OMPLPlannerDescription
~OMPLPlannerDescription()
Destructor.
Definition: moveit_config_data.h:147
moveit_setup_assistant::MoveItConfigData::getOMPLPlanners
std::vector< OMPLPlannerDescription > getOMPLPlanners() const
Definition: moveit_config_data.cpp:687
moveit_setup_assistant::MoveItConfigData
This class is shared with all widgets and contains the common configuration data needed for generatin...
Definition: moveit_config_data.h:219
moveit_setup_assistant::MoveItConfigData::outputSimpleControllersYAML
bool outputSimpleControllersYAML(const std::string &file_path)
Definition: moveit_config_data.cpp:983
moveit_setup_assistant::GenericParameter::setValue
void setValue(std::string value)
Definition: moveit_config_data.h:184
collision_detection::AllowedCollisionMatrix
moveit_setup_assistant::MoveItConfigData::setup_assistant_path_
std::string setup_assistant_path_
Setup Assistants package's path for when we use its templates.
Definition: moveit_config_data.h:294
moveit_setup_assistant::GenericParameter::comment_
std::string comment_
Definition: moveit_config_data.h:208
moveit_setup_assistant::OMPLPlannerDescription::OMPLPlannerDescription
OMPLPlannerDescription(const std::string &name, const std::string &type)
Constructor.
Definition: moveit_config_data.h:141
moveit_setup_assistant::MoveItConfigData::getPlanningScene
planning_scene::PlanningScenePtr getPlanningScene()
Provide a shared planning scene.
Definition: moveit_config_data.cpp:159
moveit_setup_assistant::MoveItConfigData::outputSetupAssistantFile
bool outputSetupAssistantFile(const std::string &file_path)
Definition: moveit_config_data.cpp:193
moveit_setup_assistant::MoveItConfigData::parseROSController
bool parseROSController(const YAML::Node &controller)
Definition: moveit_config_data.cpp:1515
moveit_setup_assistant::MoveItConfigData::GROUPS
@ GROUPS
Definition: moveit_config_data.h:230
moveit_setup_assistant::ControllerConfig::type_
std::string type_
Definition: moveit_config_data.h:118
moveit_setup_assistant::MoveItConfigData::END_EFFECTORS
@ END_EFFECTORS
Definition: moveit_config_data.h:234
moveit_setup_assistant::MoveItConfigData::getSetupAssistantYAMLPath
bool getSetupAssistantYAMLPath(std::string &path)
Definition: moveit_config_data.cpp:1746
moveit_setup_assistant::GroupMetaData::kinematics_solver_
std::string kinematics_solver_
Definition: moveit_config_data.h:102
moveit_setup_assistant::GenericParameter
Definition: moveit_config_data.h:172
model.h
moveit_setup_assistant::MoveItConfigData::getRobotModel
moveit::core::RobotModelConstPtr getRobotModel()
Provide a shared kinematic model loader.
Definition: moveit_config_data.cpp:128
moveit_setup_assistant::MoveItConfigData::outputROSControllersYAML
bool outputROSControllersYAML(const std::string &file_path)
Definition: moveit_config_data.cpp:1047
moveit_setup_assistant::MoveItConfigData::urdf_from_xacro_
bool urdf_from_xacro_
Flag indicating whether the URDF was loaded from .xacro format.
Definition: moveit_config_data.h:259
moveit_setup_assistant::GenericParameter::name_
std::string name_
Definition: moveit_config_data.h:203
moveit_setup_assistant::MoveItConfigData::urdf_string_
std::string urdf_string_
URDF robot model string.
Definition: moveit_config_data.h:267
moveit_setup_assistant::MoveItConfigData::srdf_
srdf::SRDFWriterPtr srdf_
SRDF Data and Writer.
Definition: moveit_config_data.h:284
moveit_setup_assistant::MoveItConfigData::updateRobotModel
void updateRobotModel()
Update the Kinematic Model with latest SRDF modifications.
Definition: moveit_config_data.cpp:142
moveit_setup_assistant::MoveItConfigData::author_name_
std::string author_name_
Name of the author of this config.
Definition: moveit_config_data.h:312
moveit_setup_assistant::MoveItConfigData::getControllers
std::vector< ControllerConfig > & getControllers()
Gets controller_configs_ vector.
Definition: moveit_config_data.h:485
moveit_setup_assistant::MoveItConfigData::debug_
bool debug_
Is this application in debug mode?
Definition: moveit_config_data.h:303
moveit_setup_assistant::GroupMetaData::kinematics_solver_timeout_
double kinematics_solver_timeout_
Definition: moveit_config_data.h:104
moveit_setup_assistant::MoveItConfigData::createFullURDFPath
bool createFullURDFPath()
Make the full URDF path using the loaded .setup_assistant data.
Definition: moveit_config_data.cpp:1757
moveit_setup_assistant::MoveItConfigData::appendPaths
std::string appendPaths(const std::string &path1, const std::string &path2)
Definition: moveit_config_data.cpp:1921
name
name
moveit_setup_assistant::MoveItConfigData::addGenericParameterToSensorPluginConfig
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...
Definition: moveit_config_data.cpp:2002
moveit_setup_assistant::MoveItConfigData::load3DSensorsYAML
static std::vector< std::map< std::string, GenericParameter > > load3DSensorsYAML(const std::string &file_path)
Load perception sensor config.
Definition: moveit_config_data.cpp:1863
moveit_setup_assistant::GroupMetaData::goal_orientation_tolerance_
double goal_orientation_tolerance_
Definition: moveit_config_data.h:107
moveit_setup_assistant::GroupMetaData::kinematics_parameters_file_
std::string kinematics_parameters_file_
Definition: moveit_config_data.h:108
moveit_setup_assistant::MoveItConfigData::getJointHardwareInterface
std::string getJointHardwareInterface(const std::string &joint_name)
Helper function to get the controller that is controlling the joint.
Definition: moveit_config_data.cpp:550
moveit_setup_assistant::MoveItConfigData::inputROSControllersYAML
bool inputROSControllersYAML(const std::string &file_path)
Definition: moveit_config_data.cpp:1617
moveit_setup_assistant::MoveItConfigData::~MoveItConfigData
~MoveItConfigData()
moveit_setup_assistant::GroupMetaData::goal_joint_tolerance_
double goal_joint_tolerance_
Definition: moveit_config_data.h:105
moveit_setup_assistant
Definition: compute_default_collisions.h:46
srdf::Model::GroupState
moveit_setup_assistant::MoveItConfigData::getInitialJoints
std::map< std::string, double > getInitialJoints() const
Definition: moveit_config_data.cpp:665
moveit_setup_assistant::MoveItConfigData::outputSTOMPPlanningYAML
bool outputSTOMPPlanningYAML(const std::string &file_path)
Definition: moveit_config_data.cpp:346
moveit_setup_assistant::MoveItConfigData::VIRTUAL_JOINTS
@ VIRTUAL_JOINTS
Definition: moveit_config_data.h:229
moveit_setup_assistant::GenericParameter::setName
void setName(std::string name)
Definition: moveit_config_data.h:180
moveit_setup_assistant::MoveItConfigData::allowed_collision_matrix_
collision_detection::AllowedCollisionMatrix allowed_collision_matrix_
Allowed collision matrix for robot poses.
Definition: moveit_config_data.h:306
moveit_setup_assistant::MoveItConfigData::findGroupByName
srdf::Model::Group * findGroupByName(const std::string &name)
Definition: moveit_config_data.cpp:1928
moveit_setup_assistant::MoveItConfigData::config_pkg_path_
std::string config_pkg_path_
Loaded configuration package path - if an existing package was loaded, holds that path.
Definition: moveit_config_data.h:297
moveit_setup_assistant::ControllerConfig::name_
std::string name_
Definition: moveit_config_data.h:117
moveit_setup_assistant::DEFAULT_KIN_SOLVER_TIMEOUT
static const double DEFAULT_KIN_SOLVER_TIMEOUT
Definition: moveit_config_data.h:91
planning_scene.h
moveit_setup_assistant::MoveItConfigData::urdf_model_
urdf::ModelSharedPtr urdf_model_
URDF robot model.
Definition: moveit_config_data.h:264
moveit_setup_assistant::MoveItConfigData::urdf_pkg_name_
std::string urdf_pkg_name_
Name of package containig urdf (note: this may be empty b/c user may not have urdf in pkg)
Definition: moveit_config_data.h:253
class_forward.h
moveit_setup_assistant::MoveItConfigData::xacro_args_
std::string xacro_args_
xacro arguments
Definition: moveit_config_data.h:261
moveit_setup_assistant::MoveItConfigData::controller_configs_
std::vector< ControllerConfig > controller_configs_
Controllers config data.
Definition: moveit_config_data.h:556
moveit_setup_assistant::MoveItConfigData::planning_scene_
planning_scene::PlanningScenePtr planning_scene_
Shared planning scene.
Definition: moveit_config_data.h:559
moveit_setup_assistant::GroupMetaData::default_planner_
std::string default_planner_
Definition: moveit_config_data.h:109
moveit_setup_assistant::MoveItConfigData::JointModelCompare::operator()
bool operator()(const moveit::core::JointModel *jm1, const moveit::core::JointModel *jm2) const
Definition: moveit_config_data.h:538
moveit_setup_assistant::MoveItConfigData::getDefaultStartPose
srdf::Model::GroupState getDefaultStartPose()
Helper function to get the default start pose for moveit_sim_hw_interface.
Definition: moveit_config_data.cpp:1036
moveit_setup_assistant::MoveItConfigData::changes
unsigned long changes
Definition: moveit_config_data.h:241
moveit_setup_assistant::MoveItConfigData::srdf_pkg_relative_path_
std::string srdf_pkg_relative_path_
Path relative to loaded configuration package.
Definition: moveit_config_data.h:281
srdf
moveit_setup_assistant::OmplPlanningParameter::comment
std::string comment
Definition: moveit_config_data.h:129
moveit_setup_assistant::ControllerConfig::joints_
std::vector< std::string > joints_
Definition: moveit_config_data.h:119
moveit_setup_assistant::MoveItConfigData::SIMULATION
@ SIMULATION
Definition: moveit_config_data.h:236
moveit_setup_assistant::MoveItConfigData::findControllerByName
ControllerConfig * findControllerByName(const std::string &controller_name)
Definition: moveit_config_data.cpp:1954
moveit_setup_assistant::GenericParameter::GenericParameter
GenericParameter()
Definition: moveit_config_data.h:175
srdf_writer.h
moveit_setup_assistant::MoveItConfigData::GROUP_KINEMATICS
@ GROUP_KINEMATICS
Definition: moveit_config_data.h:232
moveit_setup_assistant::MoveItConfigData::GROUP_CONTENTS
@ GROUP_CONTENTS
Definition: moveit_config_data.h:231
srdf::Model::Group
moveit_setup_assistant::MoveItConfigData::processROSControllers
bool processROSControllers(std::ifstream &input_stream)
Definition: moveit_config_data.cpp:1561
moveit_setup_assistant::GenericParameter::getComment
const std::string & getComment() const
Definition: moveit_config_data.h:200
moveit_setup_assistant::ControllerConfig
Definition: moveit_config_data.h:115
moveit_setup_assistant::MoveItConfigData::SRDF
@ SRDF
Definition: moveit_config_data.h:239
moveit_setup_assistant::MoveItConfigData::outputKinematicsYAML
bool outputKinematicsYAML(const std::string &file_path)
Definition: moveit_config_data.cpp:489
moveit_setup_assistant::OmplPlanningParameter
Definition: moveit_config_data.h:125
moveit_setup_assistant::MoveItConfigData::config_pkg_generated_timestamp_
std::time_t config_pkg_generated_timestamp_
Timestamp when configuration package was generated, if it was previously generated.
Definition: moveit_config_data.h:309
moveit_setup_assistant::MoveItConfigData::output3DSensorPluginYAML
bool output3DSensorPluginYAML(const std::string &file_path)
Definition: moveit_config_data.cpp:1198
moveit_setup_assistant::OMPLPlannerDescription
This class describes the OMPL planners by name, type, and parameter list, used to create the ompl_pla...
Definition: moveit_config_data.h:134
moveit_setup_assistant::MoveItConfigData::setRobotModel
void setRobotModel(const moveit::core::RobotModelPtr &robot_model)
Load a robot model.
Definition: moveit_config_data.cpp:120
moveit_setup_assistant::MoveItConfigData::urdf_path_
std::string urdf_path_
Full file-system path to urdf.
Definition: moveit_config_data.h:250
moveit_setup_assistant::GroupMetaData::kinematics_solver_search_resolution_
double kinematics_solver_search_resolution_
Definition: moveit_config_data.h:103
moveit_setup_assistant::MoveItConfigData::inputPlanningContextLaunch
bool inputPlanningContextLaunch(const std::string &file_path)
Definition: moveit_config_data.cpp:1474
moveit_setup_assistant::OmplPlanningParameter::name
std::string name
Definition: moveit_config_data.h:127
moveit_setup_assistant::MoveItConfigData::outputFakeControllersYAML
bool outputFakeControllersYAML(const std::string &file_path)
Definition: moveit_config_data.cpp:571
moveit::core::JointModel
moveit_setup_assistant::MOVEIT_CLASS_FORWARD
MOVEIT_CLASS_FORWARD(MoveItConfigData)
moveit_setup_assistant::GroupMetaData::goal_position_tolerance_
double goal_position_tolerance_
Definition: moveit_config_data.h:106
moveit_setup_assistant::DEFAULT_KIN_SOLVER_SEARCH_RESOLUTION
static const double DEFAULT_KIN_SOLVER_SEARCH_RESOLUTION
Definition: moveit_config_data.h:90
moveit_setup_assistant::MoveItConfigData::outputGazeboURDFFile
bool outputGazeboURDFFile(const std::string &file_path)
Definition: moveit_config_data.cpp:248
srdf::SRDFWriterPtr
std::shared_ptr< SRDFWriter > SRDFWriterPtr


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