moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
Public Member Functions | List of all members
moveit_configs_utils.moveit_configs_builder.MoveItConfigsBuilder Class Reference
Inheritance diagram for moveit_configs_utils.moveit_configs_builder.MoveItConfigsBuilder:
Inheritance graph
[legend]
Collaboration diagram for moveit_configs_utils.moveit_configs_builder.MoveItConfigsBuilder:
Collaboration graph
[legend]

Public Member Functions

 __init__ (self, str robot_name, robot_description="robot_description", Optional[str] package_name=None)
 
 robot_description (self, Optional[str] file_path=None, dict[SomeSubstitutionsType, SomeSubstitutionsType] mappings=None)
 
 robot_description_semantic (self, Optional[str] file_path=None, dict[SomeSubstitutionsType, SomeSubstitutionsType] mappings=None)
 
 robot_description_kinematics (self, Optional[str] file_path=None)
 
 joint_limits (self, Optional[str] file_path=None)
 
 moveit_cpp (self, Optional[str] file_path=None)
 
 trajectory_execution (self, Optional[str] file_path=None, bool moveit_manage_controllers=True)
 
 planning_scene_monitor (self, bool publish_planning_scene=True, bool publish_geometry_updates=True, bool publish_state_updates=True, bool publish_transforms_updates=True, bool publish_robot_description=False, bool publish_robot_description_semantic=False)
 
 sensors_3d (self, Optional[str] file_path=None)
 
 planning_pipelines (self, str default_planning_pipeline=None, List[str] pipelines=None, bool load_all=True)
 
 pilz_cartesian_limits (self, Optional[str] file_path=None)
 
 to_moveit_configs (self)
 
 to_dict (self, bool include_moveit_configs=True)
 

Detailed Description

Definition at line 140 of file moveit_configs_builder.py.

Constructor & Destructor Documentation

◆ __init__()

moveit_configs_utils.moveit_configs_builder.MoveItConfigsBuilder.__init__ (   self,
str  robot_name,
  robot_description = "robot_description",
Optional[str]   package_name = None 
)

Definition at line 154 of file moveit_configs_builder.py.

Here is the call graph for this function:
Here is the caller graph for this function:

Member Function Documentation

◆ joint_limits()

moveit_configs_utils.moveit_configs_builder.MoveItConfigsBuilder.joint_limits (   self,
Optional[str]   file_path = None 
)
Load joint limits overrides.

:param file_path: Absolute or relative path to the joint limits yaml file (w.r.t. robot_name_moveit_config).
:return: Instance of MoveItConfigsBuilder with robot_description_planning loaded.

Definition at line 305 of file moveit_configs_builder.py.

Here is the caller graph for this function:

◆ moveit_cpp()

moveit_configs_utils.moveit_configs_builder.MoveItConfigsBuilder.moveit_cpp (   self,
Optional[str]   file_path = None 
)
Load MoveItCpp parameters.

:param file_path: Absolute or relative path to the MoveItCpp yaml file (w.r.t. robot_name_moveit_config).
:return: Instance of MoveItConfigsBuilder with moveit_cpp loaded.

Definition at line 320 of file moveit_configs_builder.py.

◆ pilz_cartesian_limits()

moveit_configs_utils.moveit_configs_builder.MoveItConfigsBuilder.pilz_cartesian_limits (   self,
Optional[str]   file_path = None 
)
Load cartesian limits.

:param file_path: Absolute or relative path to the cartesian limits file (w.r.t. robot_name_moveit_config).
:return: Instance of MoveItConfigsBuilder with pilz_cartesian_limits loaded.

Definition at line 483 of file moveit_configs_builder.py.

Here is the caller graph for this function:

◆ planning_pipelines()

moveit_configs_utils.moveit_configs_builder.MoveItConfigsBuilder.planning_pipelines (   self,
str   default_planning_pipeline = None,
List[str]   pipelines = None,
bool   load_all = True 
)
Load planning pipelines parameters.

:param default_planning_pipeline: Name of the default planning pipeline.
:param pipelines: List of the planning pipelines to be loaded.
:param load_all: Only used if pipelines is None.
                 If true, loads all pipelines defined in config package AND this package.
                 If false, only loads the pipelines defined in config package.
:return: Instance of MoveItConfigsBuilder with planning_pipelines loaded.

Definition at line 424 of file moveit_configs_builder.py.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ planning_scene_monitor()

moveit_configs_utils.moveit_configs_builder.MoveItConfigsBuilder.planning_scene_monitor (   self,
bool   publish_planning_scene = True,
bool   publish_geometry_updates = True,
bool   publish_state_updates = True,
bool   publish_transforms_updates = True,
bool   publish_robot_description = False,
bool   publish_robot_description_semantic = False 
)

Definition at line 385 of file moveit_configs_builder.py.

Here is the caller graph for this function:

◆ robot_description()

moveit_configs_utils.moveit_configs_builder.MoveItConfigsBuilder.robot_description (   self,
Optional[str]   file_path = None,
dict[SomeSubstitutionsType, SomeSubstitutionsType]   mappings = None 
)
Load robot description.

:param file_path: Absolute or relative path to the URDF file (w.r.t. robot_name_moveit_config).
:param mappings: mappings to be passed when loading the xacro file.
:return: Instance of MoveItConfigsBuilder with robot_description loaded.

Definition at line 213 of file moveit_configs_builder.py.

Here is the caller graph for this function:

◆ robot_description_kinematics()

moveit_configs_utils.moveit_configs_builder.MoveItConfigsBuilder.robot_description_kinematics (   self,
Optional[str]   file_path = None 
)
Load IK solver parameters.

:param file_path: Absolute or relative path to the kinematics yaml file (w.r.t. robot_name_moveit_config).
:return: Instance of MoveItConfigsBuilder with robot_description_kinematics loaded.

Definition at line 290 of file moveit_configs_builder.py.

Here is the caller graph for this function:

◆ robot_description_semantic()

moveit_configs_utils.moveit_configs_builder.MoveItConfigsBuilder.robot_description_semantic (   self,
Optional[str]   file_path = None,
dict[SomeSubstitutionsType, SomeSubstitutionsType]   mappings = None 
)
Load semantic robot description.

:param file_path: Absolute or relative path to the SRDF file (w.r.t. robot_name_moveit_config).
:param mappings: mappings to be passed when loading the xacro file.
:return: Instance of MoveItConfigsBuilder with robot_description_semantic loaded.

Definition at line 254 of file moveit_configs_builder.py.

Here is the caller graph for this function:

◆ sensors_3d()

moveit_configs_utils.moveit_configs_builder.MoveItConfigsBuilder.sensors_3d (   self,
Optional[str]   file_path = None 
)
Load sensors_3d parameters.

:param file_path: Absolute or relative path to the sensors_3d yaml file (w.r.t. robot_name_moveit_config).
:return: Instance of MoveItConfigsBuilder with robot_description_planning loaded.

Definition at line 407 of file moveit_configs_builder.py.

Here is the caller graph for this function:

◆ to_dict()

moveit_configs_utils.moveit_configs_builder.MoveItConfigsBuilder.to_dict (   self,
bool   include_moveit_configs = True 
)
Get loaded parameters from robot_name_moveit_config as a dictionary.

:param include_moveit_configs: Whether to include the MoveIt config parameters or
                               only the ones from ParameterBuilder
:return: Dictionary with all parameters loaded.

Definition at line 535 of file moveit_configs_builder.py.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ to_moveit_configs()

moveit_configs_utils.moveit_configs_builder.MoveItConfigsBuilder.to_moveit_configs (   self)
Get MoveIt configs from robot_name_moveit_config.

:return: An MoveItConfigs instance with all parameters loaded.

Definition at line 506 of file moveit_configs_builder.py.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ trajectory_execution()

moveit_configs_utils.moveit_configs_builder.MoveItConfigsBuilder.trajectory_execution (   self,
Optional[str]   file_path = None,
bool   moveit_manage_controllers = True 
)
Load trajectory execution and moveit controller managers' parameters

:param file_path: Absolute or relative path to the controllers yaml file (w.r.t. robot_name_moveit_config).
:param moveit_manage_controllers: Whether trajectory execution manager is allowed to switch controllers' states.
:return: Instance of MoveItConfigsBuilder with trajectory_execution loaded.

Definition at line 332 of file moveit_configs_builder.py.

Here is the call graph for this function:
Here is the caller graph for this function:

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