Code Documentation
Robot objects
- class pybullet_industrial.robot_base.RobotBase(urdf_model: str, start_position: <Mock name='mock.array' id='140493028895840'>, start_orientation: <Mock name='mock.array' id='140493028895840'>, default_endeffector: str = None)[source]
A Base class encapsulating a URDF based industrial robot manipulator
- Parameters:
urdf_model (str) – A valid path to a urdf file
start_position (np.array) – The start position of the robot base
start_orientation (np.array) – A quaternion describing the start orientation of the robot base
default_endeffector (str, optional) – The default endeffector used when controlling the robots position
- get_endeffector_pose(endeffector_name: str = None)[source]
Returns the position of the endeffector in world coordinates
- Parameters:
endeffector (str, optional) – The name of a different endeffector link
- Returns:
The position of the endeffector np.array: The orientation of the endeffector as a quaternion
- Return type:
np.array
- get_joint_state()[source]
Returns the position of each joint as a dictionary keyed with their name
- Returns:
The state of all joinst
- Return type:
Dict[str,Dict[str,float]]
- get_world_state()[source]
Returns the position and orientation of the robot relative to the world
- Returns:
the 3 dimensional position vector of the robot base list: a 4 dimensional quaternion representing the orientation of the robot base
- Return type:
list
- reset_robot(start_position: <Mock name='mock.array' id='140493028895840'>, start_orientation: <Mock name='mock.array' id='140493028895840'>, joint_values: list = None)[source]
resets the robots joints to 0 and the base to a specified position and orientation
- Parameters:
start_position (np.array) – a 3 dimensional position
start_orientation (np.array) – a 4 dimensional quaternion representing the desired orientation
joint_values (list) – Allows to reset the joint state of the robot given a list of positions. Defaults to None in which case the joints remain in their current configuration.
- set_endeffector_pose(target_position: <Mock name='mock.array' id='140493028895840'>, target_orientation: <Mock name='mock.array' id='140493028895840'> = None, endeffector_name: str = None)[source]
Sets the pose of a robots endeffector
- Parameters:
target_position (np.array) – The desired 3D position
target_orientation (np.array, optional) – The desired orientation as a quaternion. Defaults to None.
endeffector_name (str, optional) – The name of a different endeffector. Defaults to None.
- set_joint_position(target: Dict[str, float], ignore_limits=False)[source]
- Sets the target position for a number of joints.
The maximum force of each joint is set according to the max_joint_force class attribute.
- Parameters:
target (Dict[str, float]) – A dictionary containing the joint states to be set
- Raises:
KeyError – If the specified joint state is not part of the Robot
- set_world_state(start_position: <Mock name='mock.array' id='140493028895840'>, start_orientation: <Mock name='mock.array' id='140493028895840'>)[source]
Resets the robots base to a specified position and orientation
- Parameters:
start_position (np.array) – a 3 dimensional position
start_orientation (np.array) – a 4 dimensional quaternion representing the desired orientation
Endeffector tools
- class pybullet_industrial.endeffector_tool.EndeffectorTool(urdf_model: str, start_position: <Mock name='mock.array' id='140493028895840'>, start_orientation: <Mock name='mock.array' id='140493028895840'>, coupled_robot: ~pybullet_industrial.robot_base.RobotBase = None, tcp_frame: str = None, connector_frame: str = None)[source]
The base class for all Tools and Sensors connected to a Robot
- Parameters:
urdf_model (str) – A valid path to a urdf file describint the tool geometry
start_position (np.array) – the position at which the tool should be spawned
start_orientation (np.array) – the orientation at which the tool should be spawned
coupled_robot (pi.RobotBase, optional) – A pybullet_omdistrial.RobotBase object if the robot is coupled from the start. Defaults to None.
tcp_frame (str, optional) – The name of the urdf_link describing the tool center point. Defaults to None in which case the last link is used.
connector_frame (str, optional) – The name of the urdf_link at which a robot connects. Defaults to None in which case the base link is used.
- apply_tcp_force(force: <Mock name='mock.array' id='140493028895840'>, world_coordinates: bool = True)[source]
Function which can apply a external Force at a the next simulation step.
Carefull, this does not behave as expected for setRealTimeSimulation(1)!
- Parameters:
force (np.array) – A 3 dimensional force vector in Newton.
world_coordinates (bool, optional) – Specify wheter the force is defined in the world coordinates or the relative link frame. Defaults to True.
- apply_tcp_torque(torque: <Mock name='mock.array' id='140493028895840'>)[source]
- Function which can apply a external Torque at a the next simulation step.
The local tcp_link frames are used as the main torque axis.
Carefull, this does not behave as expected for setRealTimeSimulation(1)!
- Parameters:
torque (np.array) – A 3 dimensional torque vector in Newtonmeter.
- couple(robot: RobotBase, endeffector_name: str = None)[source]
Dynamically Couples the Tool with the Endeffector of a given robot. Note that this endeffector can also be a virtual link to connect a sensor. A Tool can only be coupled with one robot
- Parameters:
robot (pybullet_industrial.RobotBase) – The robot whith which the tool should couple.
endeffector_name (str, optional) – The endeffector of the robot where the tool should couple to. Defaults to None.
- Raises:
ValueError – If the tool is already coupled.
TypeError – if the object to couple is nof of class RobotBase.
- decouple()[source]
Decouples the tool from the current robot. In this case a new constraint is created rooting the tool in its current pose.
- get_tool_pose(tcp_frame: str = None)[source]
- Returns the pose of the tool center point.
Using the tcp_frame argument the state of other links can also be returned
- Parameters:
tcp_frame (str, optional) – the name of the link whose pose should be returned. Defaults to None in which case the default tcp is used
- Returns:
The 3D position the link the world coordinate system np.array: A quaternion describing the orientation of the link in world coordinates
- Return type:
np.array
- is_coupled()[source]
Function which returns true if the Tool is currently coupled to a robot
- Returns:
1 if the tool is coupled, 0 if not
- Return type:
bool
- set_tool_pose(target_position: <Mock name='mock.array' id='140493028895840'>, target_orientation: <Mock name='mock.array' id='140493028895840'> = None)[source]
- Allows the control of the tool.
If the tool is coupled the inverse kinematic control of a coupled robot is used. If not the tool is moved directly.
- Parameters:
target_position (np.array) – the desired position of the tool center point (tcp)
target_orientation (np.array, optional) – the desired position of the tool center point (tcp). If none is provided only the position of the robot is controlled.
- class pybullet_industrial.raycaster.RayCaster(urdf_model: str, start_position: <Mock name='mock.array' id='140493028895840'>, start_orientation: <Mock name='mock.array' id='140493028895840'>, raycast_properties: ~typing.Dict, coupled_robot: ~pybullet_industrial.robot_base.RobotBase = None, tcp_frame: str = None, connector_frame: str = None)[source]
Special Endeffector Tool which can cast rays. Base for Extruder and Remover classes.
- Parameters:
urdf_model (str) – A valid path to a urdf file describint the tool geometry
start_position (np.array) – the position at which the tool should be spawned
start_orientation (np.array) – the orientation at which the tool should be spawned
raycast_properties (Dict) – A dictionary containing the properties of the extrusion head. During initialization only ‘material’ has to be set. Default Values are: ‘opening angle’:0,’number of rays’:1, ‘maximum distance’:1
coupled_robot (RobotBase, optional) – A pybullet_industrial.RobotBase object if the robot is coupled from the start. Defaults to None.
tcp_frame (str, optional) – The name of the urdf_link describing the tool center point. Defaults to None in which case the last link is used.
connector_frame (str, optional) – The name of the urdf_link at which a robot connects. Defaults to None in which case the base link is used.
- cast_rays(position: <Mock name='mock.array' id='140493028895840'>, orientation: <Mock name='mock.array' id='140493028895840'>)[source]
Randomly casts rays withn a given range from a specified position and orientation
- Parameters:
position (np.array) – start position of the raycast
orientation (np.array) – start orientation of the raycast
- Returns:
The result of a raycast
- Return type:
List
Adding material
- class pybullet_industrial.extruder.Extruder(urdf_model: str, start_position: <Mock name='mock.array' id='140493028895840'>, start_orientation: <Mock name='mock.array' id='140493028895840'>, extruder_properties: ~typing.Dict, coupled_robot: ~pybullet_industrial.robot_base.RobotBase = None, tcp_frame: str = None, connector_frame: str = None)[source]
Special Endeffector Tool which can extrude material from its tcp.
- Parameters:
urdf_model (str) – A valid path to a urdf file describint the tool geometry
start_position (np.array) – the position at which the tool should be spawned
start_orientation (np.array) – the orientation at which the tool should be spawned
extruder_properties (Dict) –
A dictionary containing the properties of the extrusion head. During initialization only ‘material’ has to be set. Default Values are: ‘opening angle’:0,’number of rays’:1, ‘material properties’: {‘particle size’:0.03,
’color’ : [1, 0, 0, 1]},
’maximum distance’:1,’material’:Particle,
coupled_robot (RobotBase, optional) – A pybullet_industrial.RobotBase object if the robot is coupled from the start. Defaults to None.
tcp_frame (str, optional) – The name of the urdf_link describing the tool center point. Defaults to None in which case the last link is used.
connector_frame (str, optional) – The name of the urdf_link at which a robot connects. Defaults to None in which case the base link is used.
- Raises:
ValueError – If no material is provided during initialization.
- calculate_process_force(ray_cast_results, tcp_frame=None)[source]
Function calculating the process force of the milling tool.
- Parameters:
ray_cast_results (list) – The result of a batch ray cast as performed by the remove function
tcp_frame (str) – The name of the tool center point frame. Defaults to None.
- Returns:
a 3 dimensional array containing the process force in the x,y,z direction
- Return type:
np.array
Removing material
- class pybullet_industrial.remover.Remover(urdf_model: str, start_position: <Mock name='mock.array' id='140493028895840'>, start_orientation: <Mock name='mock.array' id='140493028895840'>, remover_properties: ~typing.Dict, coupled_robot: ~pybullet_industrial.robot_base.RobotBase = None, tcp_frame: str = None, connector_frame: str = None)[source]
Special Remover Tool which can remove objects from the simulation.
- Parameters:
urdf_model (str) – A valid path to a urdf file describint the tool geometry
start_position (np.array) – the position at which the tool should be spawned
start_orientation (np.array) – the orientation at which the tool should be spawned
remover_properties (Dict) – A dictionary containing the properties of the extrusion head. During initialization only ‘material’ has to be set. Default Values are: ‘opening angle’:0,’number of rays’:1, ‘maximum distance’:1
coupled_robot (RobotBase, optional) – A pybullet_industrial.RobotBase object if the robot is coupled from the start. Defaults to None.
tcp_frame (str, optional) – The name of the urdf_link describing the tool center point. Defaults to None in which case the last link is used.
connector_frame (str, optional) – The name of the urdf_link at which a robot connects. Defaults to None in which case the base link is used.
- calculate_process_force(ray_cast_results, tcp_frame=None)[source]
Function calculating the process force of the milling tool.
- Parameters:
ray_cast_results (list) – The result of a batch ray cast as performed by the remove function
tcp_frame (str) – The name of the tool center point frame. Defaults to None.
- Returns:
a 3 dimensional array containing the process force in the x,y,z direction
- Return type:
np.array
- class pybullet_industrial.milling_tool.MillingTool(urdf_model: str, start_position: <Mock name='mock.array' id='140493028895840'>, start_orientation: <Mock name='mock.array' id='140493028895840'>, milling_properties: ~typing.Dict, coupled_robot: ~pybullet_industrial.robot_base.RobotBase = None, tcp_frame: str = None, connector_frame: str = None)[source]
A class implementing a milling tool. The tool is modeled as a set of teeth that remove material and apply forces on the tcp frame according to the kienzle model.
- Parameters:
urdf_model (str) – The path to the urdf model of the milling tool
start_position (np.array) – The position of the tool center point
start_orientation (np.array) – The orientation of the tool center point
milling_properties (Dict) – A dictionary containing the properties of the milling tool. Default values are: ‘diameter’:0.05, ‘height’:0.01, ‘number of rays’:10,’rotation speed’:0.1, ‘number of teeth’:5 ‘material_specific_force’:2500,’chip_thickness_exponent’:0.26 The parameters kc11 and m_c are specific for the material.
coupled_robot (RobotBase, optional) – A pybullet_industrial.RobotBase object if the robot is coupled from the start. Defaults to None.
tcp_frame (str, optional) – The name of the urdf_link describing the tool center point. Defaults to None in which case the last link is used.
connector_frame (str, optional) – The name of the urdf_link at which a robot connects. Defaults to None in which case the base link is used
- calculate_process_force(ray_cast_results, tcp_frame=None)[source]
Function calculating the process force of the milling tool.
- Parameters:
ray_cast_results (list) – The result of a batch ray cast as performed by the mill function
tcp_frame (str) – The name of the tool center point frame. Defaults to None.
- Returns:
a 3 dimensional array containing the process force in the x,y,z direction
- Return type:
np.array
- cast_rays(position: <Mock name='mock.array' id='140493028895840'>, orientation: <Mock name='mock.array' id='140493028895840'>, debug=False)[source]
Randomly casts rays withn a given range from a specified position and orientation
- Parameters:
position (np.array) – start position of the raycast
orientation (np.array) – start orientation of the raycast
debug (bool, optional) – If true, the debug lines are drawn. Defaults to False.
- Returns:
The result of a raycast
- Return type:
List
- change_properties(new_properties: Dict)[source]
Allows retroactive changes to the ray casting properties.
- Parameters:
new_properties (Dict) – A dictionary containing values and keys that should be changed
- Raises:
KeyError – If a key is not a valid property
- force_model(cutting_speed, cutting_depth, teeth_angles)[source]
A force model that is used to calculate the force that is applied to the tool. :param cutting_speed: the speed at which the cutting tool is moved into the material :type cutting_speed: float :param cutting_depth: an array of the depth of the cutting tool at each tooth :type cutting_depth: np.array :param teeth_angles: the angles of the teeth on the tool :type teeth_angles: list
- Returns:
an array of the force that is applied to the cutting tool at the tcp
- Return type:
np.array
- get_cutting_state(ray_cast_result, tcp_frame=None)[source]
A helpfer function calculating the cutting depth and speed of the tool.
- Parameters:
ray_cast_result (list) – The result of a batch ray cast as performed by the mill function
tcp_frame (str, optional) – The tool center point frame name. Defaults to None.
- Returns:
the speed at which the cutting tool is moved into the material (np.array): an array of the depth of the cutting tool at each tooth
- Return type:
float
- mill(tcp_frame=None, debug=False)[source]
Function that performs a milling operation.
- Parameters:
tcp_frame (str, optional) – The name of the tool center point frame. Defaults to None.
debug (bool, optional) – If true, the debug lines are drawn. Defaults to False.
- Returns:
A list containing the ids of the bodies that were removed
- Return type:
list
Moving material
- class pybullet_industrial.gripper.Gripper(urdf_model: str, start_position, start_orientation, coupled_robots=None, tcp_frame=None, connector_frames=None)[source]
The base class for all Tools and Sensors connected to a Robot
- Parameters:
urdf_model (str) – A valid path to a urdf file describing the tool geometry
start_position (np.array) – the position at which the tool should be spawned
start_orientation (np.array) – the orientation at which the tool should be spawned
coupled_robots (pi.RobotBase, optional) – A wbk_sim.Robot object if the robot is coupled from the start. Defaults to None.
tcp_frame (str, optional) – The name of the urdf_link describing the tool center point. Defaults to None in which case the last link is used.
connector_frames (str, optional) – The name of the urdf_link at which a robot connects. Defaults to None in which case the base link is used.
- class pybullet_industrial.gripper.SuctionGripper(urdf_model: str, start_position, start_orientation, coupled_robots=None, tcp_frame=None, connector_frames=None, suction_links=None)[source]
The base class for all Tools and Sensors connected to a Robot
- Parameters:
urdf_model (str) – A valid path to a urdf file describing the tool geometry
start_position (np.array) – the position at which the tool should be spawned
start_orientation (np.array) – the orientation at which the tool should be spawned
coupled_robots (pi.RobotBase, optional) – A wbk_sim.Robot object if the robot is coupled from the start. Defaults to None.
tcp_frame (str, optional) – The name of the urdf_link describing the tool center point. Defaults to None in which case the last link is used.
connector_frames (str, optional) – The name of the urdf_link at which a robot connects. Defaults to None in which case the base link is used.
suction_links (str, optional) – The names of the urdf_links wich represent the active suction parts. Defaults to all Links.
- activate(tolerance=0.0001)[source]
Function to activate the suction gripper creating constraints between gripper and object
- Parameters:
tolerance (float, optional) – tolerance of contacts, i.e. at which distance the contact point is considered relevant.
- Returns:
ids of coupled objects
- Return type:
list[int]
Sensing
- class pybullet_industrial.sensors.Camera(urdf_model: str, start_position: <Mock name='mock.array' id='140493028895840'>, start_orientation: <Mock name='mock.array' id='140493028895840'>, camera_parameters: ~typing.Dict, coupled_robot: ~pybullet_industrial.robot_base.RobotBase = None, camera_frame: str = None, connector_frame: str = None)[source]
Special Endeffector Tool which can cast rays. Base for Extruder and Remover classes.
- Parameters:
urdf_model (str) – A valid path to a urdf file describint the tool geometry
start_position (np.array) – the position at which the tool should be spawned
start_orientation (np.array) – the orientation at which the tool should be spawned
camera_parameters (Dict[str,float]) – A dictionary containing the camera parameters. Default Values are: ‘width’: 480, ‘height’: 240, ‘fov’: 60, ‘aspect ratio’: 1, ‘near plane distance’: 0.01, ‘far plane distance’: 100
coupled_robot (RobotBase, optional) – A pybullet_industrial.RobotBase object if the robot is coupled from the start. Defaults to None.
camera_frame (str, optional) – The name of the urdf_link at which the camera is located. Defaults to None in which case the last link is used.
connector_frame (str, optional) – The name of the urdf_link at which a robot connects. Defaults to None in which case the base link is used.
Materials
- class pybullet_industrial.material.MetalVoxel(ray_cast_result: list, material_properties: Dict)[source]
A simple voxel class for cutting and milling simulations
- Parameters:
ray_cast_result (list) – The result of a pybullet ray_cast as performed by the Extruder class.
material_properties (Dict) – A dictionary containing the properties of the material. The default properties for a Metal Voxel are: ‘particle size’: 0.3, ‘color’: [1, 0, 0, 1]
- class pybullet_industrial.material.Paint(ray_cast_result: list, material_properties: Dict)[source]
- A class for simple Paint particles which stick to objects and move with them.
The Paint particles are purely visible and have neither mass nor a collision mesh
- Parameters:
ray_cast_result (list) – The result of a pybullet ray_cast as performed by the extruder
material_properties (Dict) – A dictionary containing the properties of the material. The default properties for Paint are: ‘particle size’: 0.3, ‘color’: [1, 0, 0, 1]
- get_position()[source]
Returns the position of a particle in the world frame
- Returns:
- The three dimensional position of the particle
in the world coordinate system
- Return type:
[float,float,float]
- static get_target_pose(target_id: int, target_link_id: int)[source]
Returns the pose of a target objects link.
This function is used to calculate the relative position of the paint particle to the object it sticks to.
- Parameters:
target_id (int) – The unique id of the target object
target_link_id (int) – The link id of the target object
- Returns:
The position and orientation of the target object
- Return type:
np.array, np.array
- class pybullet_industrial.material.Particle(ray_cast_result: list, material_properties: Dict)[source]
A template class for material particles extruded by a extruder endeffector tool.
All materials should inherit from this class and implement its methods.
- Parameters:
ray_cast_result (list) –
The result of a pybullet ray_cast as performed by the Extruder class. It is made up of: [objectUniqueId,
linkIndex, hit fraction, hit position, hit normal]
material_properties (Dict) – A dictionary containing the properties of the material
- class pybullet_industrial.material.Plastic(ray_cast_result: list, material_properties: Dict)[source]
- A class for simple particles which can be used for additive manufacturing.
The particles are infinitely rigid and stick to each other.
- Parameters:
ray_cast_result (list) –
The result of a pybullet ray_cast as performed by the Extruder class. It is made up of: [objectUniqueId,
linkIndex, hit fraction, hit position, hit normal]
material_properties (Dict) – A dictionary containing the properties of the material. The default properties for Plastic are: ‘particle size’: 0.3, ‘color’: [1, 0, 0, 1]
- pybullet_industrial.material.spawn_material_block(base_position: list, dimensions: list, material: Particle, material_properties: Dict)[source]
Spawns a block of a give material.
- Parameters:
base_position ([float,float,float]) – The position of the lower left base corner of the block
dimensions ([float,float,float]) – The dimensions of the block in [width,breath,height]
material (Particle) – A particle that should be spawned
material_properties (Dict) – A dictionary containing the properties of the material. It needs to contain a key ‘particle size’.
- Returns:
A list of the spawned particles
- Return type:
list[Particle]
Toolpaths
- class pybullet_industrial.toolpath.ToolPath(positions: <Mock name='mock.array' id='140493028895840'>, orientations: <Mock name='mock.array' id='140493028895840'> = None, tool_acivations: <Mock name='mock.array' id='140493028895840'> = None)[source]
A Base object for representing a toolpaths
- Parameters:
positions (np.array(3,n)) – A 3 dimensional array whith each dimension containing subsequent positions.
orientations (np.array(4,n), optional) – A 4 dimensional array where each dimension describes a subsequent quaternion. Defaults to None in which case the orientation [0,0,0,1] is assumed.
tool_acivations (np.array(n), optional) – A 1 dimensional array with boolean values describing wheter a tool is active at a given path pose. Defaults to None in which case the tool is always inactive.
- Raises:
ValueError – If all given input arrays are different lengths.
- append(tool_path)[source]
Appends a given ToolPath object to the end of this tool path.
- Parameters:
tool_path (ToolPath) – Another ToolPath object.
- draw(pose: bool = False, color: list = [0, 0, 1])[source]
- Function which draws the path into the Debugin GUI.
The path can either be a line representing the positions or a series of coordinate systems representing the whole pose.
- Parameters:
orientation (bool, optional) – Flag which determins if only the path position is shown or the full pose. Defaults to False.
color (list, optional) – The color of the line used for position only drawing. Defaults to [0, 0, 1].
- get_start_pose()[source]
Returns the start pose of the trajectory for initial positioning
- Returns:
a 3D position vector np.array: a 4D quaternion describing the orientation
- Return type:
np.array
- prepend(tool_path)[source]
Prepends a given ToolPath object to the start of this tool path.
- Parameters:
tool_path (ToolPath) – Another ToolPath object.
- pybullet_industrial.path_builders.build_box_path(center_position: <Mock name='mock.array' id='140493028895840'>, dimensions: <Mock name='mock.array' id='140493028895840'>, radius: float, orientation: <Mock name='mock.array' id='140493028895840'>, samples: int)[source]
Build a box shaped path with rounded corners
- Parameters:
center_position (np.array) – The 3D center position of the box
dimensions (np.array) – the length and width of the box
radius (float) – the radius of the corners
orientation (np.array) – A quaternion describing the orientation of the box
samples (int) – The number of points in the box path
- Returns:
The resulting Toolpath
- Return type:
Utility functionality
- pybullet_industrial.utility.draw_coordinate_system(position: <Mock name='mock.array' id='140493028895840'>, orientation: <Mock name='mock.array' id='140493028895840'>, length: float = 0.1, width: float = 2.0, life_time: float = 0, parent_id: int = -1, parent_index: int = -1)[source]
This function draws a coordinate system at a given position
- Parameters:
position (np.array) – The 3D position of the coordinate system
orientation (np.array) – The quaternion representing the orientation of the coordinate system
length (float, optional) – The length of the lines. Defaults to 0.5.
width (float, optional) – The width of the lines. Defaults to 2.0.
life_time (float, optional) – How long the coordinate system remains before despawning. Defaults to 0 in wich case it remains forever.
- pybullet_industrial.utility.draw_path(path: <Mock name='mock.array' id='140493028895840'>, color: list = [0.0, 1.0, 0.0], width: float = 2.0)[source]
Draws a path in the workspace
- Parameters:
path (np.array(3,n)) – Array containing the points in the path
color (list, optional) – RGB color. Defaults to [0.0,1.0,0.0].
width (float, optional) – The width of the lines. Defaults to 2.0.
- pybullet_industrial.utility.draw_point(point: <Mock name='mock.array' id='140493028895840'>, color: list = [0.0, 1.0, 0.0], length: float = 0.05, width: float = 2.0)[source]
Draws a point in the worldspace as a cross of 3 lines
- Parameters:
pnt (np.array) – 3 dimensional point
color (list, optional) – RGB color. Defaults to [0.0,1.0,0.0].
length (float, optional) – The length of the lines. Defaults to 0.5.
width (float, optional) – The width of the lines. Defaults to 2.0.
- pybullet_industrial.utility.draw_robot_frames(robot: RobotBase, text_size: int = 1, length: float = 0.1, width: float = 2.0, life_time: float = 0)[source]
Visualizes the coordinate Frames of each link of a robot
- Parameters:
robot (RobotBase) – a Robot object
text_size (int, optional) – The size at which the text is rendered. Defaults to 1.
length (float, optional) – The length of the lines. Defaults to 0.1.
width (float, optional) – The width of the lines. Defaults to 2.0.
life_time (float, optional) – How long the coordinate system remains before despawning. Defaults to 0 in wich case it remains forever.