Simulator

class compas_fab.fab.robots.rfl.Simulator(host='127.0.0.1', port=19997, scale=1000.0, debug=False)[source]

Bases: object

Interface to run simulations on the RFL using VREP as the engine for inverse kinematics.

Simulator is a context manager type, so it’s best used in combination with the with statement to ensure resource deallocation.

Parameters:
  • host (str) – IP address or DNS name of the V-REP simulator.
  • port (int) – Port of the simulator.
  • scale (int) – Scaling of the model. Defaults to millimeters (1000).
  • debug (bool) – True to enable debug messages, False otherwise.

Examples

>>> from compas_fab.fab.robots.rfl import *
>>> with Simulator() as simulator:
...     print ('Connected: %s' % simulator.is_connected())
...
Connected: True
SUPPORTED_ALGORITHMS = ('bitrrt', 'bkpiece1', 'est', 'kpiece1', 'lazyprmstar', 'lbkpiece1', 'lbtrrt', 'pdst', 'prm', 'prrt', 'rrt', 'rrtconnect', 'rrtstar', 'sbl', 'stride', 'trrt')
_find_path_plan(robot, goal, metric_values, collision_meshes, algorithm, trials, resolution, gantry_joint_limits, arm_joint_limits, shallow_state_search, optimize_path_length)[source]
_find_raw_robot_states(robot, goal_pose, gantry_joint_limits, arm_joint_limits, max_trials=None, max_results=1)[source]
add_building_member(robot, building_member_mesh)[source]

Adds a building member to the RFL scene and attaches it to the robot.

Parameters:
  • robot (Robot) – Robot instance to attach the building member to.
  • building_member_mesh (compas.datastructures.mesh.Mesh) – Mesh of the building member that will be attached to the robot.
Returns:

int – Object handle (identifier) assigned to the building member.

Note

All meshes are automatically removed from the scene when the simulation ends.

add_meshes(meshes)[source]

Adds meshes to the RFL scene.

Parameters:meshes (list of compas.datastructures.mesh.Mesh) – List of meshes to add to the current simulation scene.
Returns:list – List of object handles (identifiers) assigned to the meshes.

Note

All meshes are automatically removed from the scene when the simulation ends.

find_path_plan(robot, goal_pose, metric_values=None, collision_meshes=None, algorithm='rrtconnect', trials=1, resolution=0.02, gantry_joint_limits=None, arm_joint_limits=None, shallow_state_search=True, optimize_path_length=False)[source]

Find a path plan to move the selected robot from its current position to the goal_pose.

Parameters:
  • robot (Robot) – Robot instance to move.
  • goal_pose (Pose) – Target or goal pose instance.
  • metric_values (list of float) – 9 float values (3 for gantry + 6 for joints) ranging from 0 to 1, where 1 indicates the axis/joint is blocked and cannot move during inverse kinematic solving.
  • collision_meshes (list of compas.datastructures.mesh.Mesh) – Collision meshes to be taken into account when calculating the motion plan. Defaults to None.
  • algorithm (str) – Name of the algorithm to use. Defaults to rrtconnect.
  • trials (int) – Number of search trials to run. Defaults to 1.
  • resolution (float) – Validity checking resolution. This value is specified as a fraction of the space’s extent. Defaults to 0.02.
  • gantry_joint_limits (list of float) – List of 6 floats defining the upper/lower limits of gantry joints. Use this if you want to restrict the working area of the path planner.
  • arm_joint_limits (list of float) – List of 12 floats defining the upper/lower limits of arm joints. Use this if you want to restrict the working area of the path planner.
  • shallow_state_search (bool) – True to search only a minimum of valid states before searching a path, False to search states intensively.
  • optimize_path_length (bool) – True to search the path with minimal total length among all trials, False to return the first valid path found. It only affects the output if trials > 1.
Returns:

list – List of Configuration objects representing the collision-free path to the goal_pose.

find_path_plan_to_config(robot, goal_configs, metric_values=None, collision_meshes=None, algorithm='rrtconnect', trials=1, resolution=0.02, gantry_joint_limits=None, arm_joint_limits=None, shallow_state_search=True, optimize_path_length=False)[source]

Find a path plan to move the selected robot from its current position to one of the goal_configs.

This function is useful when it is required to get a path plan that ends in one specific goal configuration.

Parameters:
  • robot (Robot) – Robot instance to move.
  • goal_configs (list of Configuration) – List of target or goal configurations.
  • metric_values (list of float) – 9 float values (3 for gantry + 6 for joints) ranging from 0 to 1, where 1 indicates the axis/joint is blocked and cannot move during inverse kinematic solving.
  • collision_meshes (list of compas.datastructures.mesh.Mesh) – Collision meshes to be taken into account when calculating the motion plan. Defaults to None.
  • algorithm (str) – Name of the algorithm to use. Defaults to rrtconnect.
  • trials (int) – Number of search trials to run. Defaults to 1.
  • resolution (float) – Validity checking resolution. This value is specified as a fraction of the space’s extent. Defaults to 0.02.
  • gantry_joint_limits (list of float) – List of 6 floats defining the upper/lower limits of gantry joints. Use this if you want to restrict the working area of the path planner.
  • arm_joint_limits (list of float) – List of 12 floats defining the upper/lower limits of arm joints. Use this if you want to restrict the working area of the path planner.
  • shallow_state_search (bool) – True to search only a minimum of valid states before searching a path, False to search states intensively.
  • optimize_path_length (bool) – True to search the path with minimal total length among all trials, False to return the first valid path found. It only affects the output if trials > 1.
Returns:

list – List of Configuration objects representing the collision-free path to the goal_pose.

find_robot_states(robot, goal_pose, metric_values=None, gantry_joint_limits=None, arm_joint_limits=None, max_trials=None, max_results=1)[source]

Finds valid robot configurations for the specified goal pose.

Parameters:
  • robot (Robot) – Robot instance.
  • goal_pose (Pose) – Target or goal pose instance.
  • metric_values (list of float) – 9 float values (3 for gantry + 6 for joints) ranging from 0 to 1, where 1 indicates the axis is blocked and cannot move during inverse kinematic solving.
  • gantry_joint_limits (list of float) – List of 6 floats defining the upper/lower limits of gantry joints. Use this if you want to restrict the area in which to search for states.
  • arm_joint_limits (list of float) – List of 12 floats defining the upper/lower limits of arm joints. Use this if you want to restrict the working area in which to search for states.
  • max_trials (int) – Number of trials to run. Set to None to retry infinitely.
  • max_results (int) – Maximum number of result states to return.
Returns:

list – List of Configuration objects representing the collision-free configuration for the goal_pose.

get_all_visible_handles()[source]

Gets a list of object handles (identifiers) for all visible shapes of the RFL model.

Returns:list – List of object handles (identifiers) of the RFL model.
get_object_handle(object_name)[source]

Gets the object handle (identifier) for a given object name.

Parameters:object_name (str) – Name of the object.
Returns:int – Object handle.
get_object_matrices(object_handles)[source]

Gets a dictionary of matrices keyed by object handle.

Parameters:object_handles (list of float) – List of object handles (identifiers) to retrieve matrices from.
Returns:dict – Dictionary of matrices represented by a list of 12 float values.

Examples

>>> from compas_fab.fab.robots.rfl import Simulator
>>> with Simulator() as simulator:
...     matrices = simulator.get_object_matrices([0])
...     print(map(int, matrices[0]))
[87, 242, 966, -11851, 996, -21, -85, 6233, 0, 970, -243, 5785]

Note

The resulting dictionary is keyed by object handle.

get_robot_config(robot)[source]

Gets the current configuration of the specified robot.

Parameters:robot (Robot) – Robot instance.

Examples

>>> from compas_fab.fab.robots.rfl import Robot
>>> with Simulator() as simulator:
...     config = simulator.get_robot_config(Robot(11))
Returns:An instance of Configuration.
is_connected()[source]

Indicates whether the simulator has an active connection.

Returns:bool – True if connected, False otherwise.
pick_building_member(robot, building_member_mesh, pickup_pose, metric_values=None)[source]

Picks up a building member and attaches it to the robot.

Parameters:
  • robot (Robot) – Robot instance to use for pick up.
  • building_member_mesh (compas.datastructures.mesh.Mesh) – Mesh of the building member that will be attached to the robot.
  • pickup_pose (Pose) – Pickup pose instance.
  • metric_values (list of float) – 9 float values (3 for gantry + 6 for joints) ranging from 0 to 1, where 1 indicates the axis/joint is blocked and cannot move during inverse kinematic solving.
Returns:

int – Object handle (identifier) assigned to the building member.

remove_meshes(mesh_handles)[source]

Removes meshes from the RFL scene.

This is functionally identical to remove_objects, but it’s here for symmetry reasons.

Parameters:mesh_handles (list of int) – Object handles to remove.
remove_objects(object_handles)[source]

Removes objects from the RFL scene.

Parameters:object_handles (list of int) – Object handles to remove.

Note

Please note there’s no need to clean up objects manually after the simulation has completed, as those will be reset automatically anyway. This method is only useful if you need to remove objects during a simulation.

reset_all_robots()[source]

Resets all robots in the RFL to their base configuration.

Examples

>>> from compas_fab.fab.robots.rfl import Simulator
>>> with Simulator() as simulator:
...     simulator.reset_all_robots()
...
run_child_script(function_name, in_ints, in_floats, in_strings)[source]
set_robot_config(robot, config)[source]

Moves the robot the the specified configuration.

Parameters:

Examples

>>> from compas_fab.fab.robots.rfl import Robot, Configuration
>>> with Simulator() as simulator:
...     config = Configuration.from_joints_and_external_axes([90, 0, 0, 0, 0, -90],
...                                                          [7600, -4500, -4500])
...     simulator.set_robot_config(Robot(11), config)
...
set_robot_metric(robot, metric_values)[source]

Assigns a metric defining relations between axis values of a robot.

It takes a list of 9 float values (3 for gantry + 6 for joints) ranging from 0 to 1, where 1 indicates the axis is blocked and cannot move during inverse kinematic solving. A value of 1 on any of these effectively removes one degree of freedom (DOF).

Parameters:
  • robot (Robot) – Robot instance.
  • metric_values (list of float) – 9 float values from 0 to 1.
set_robot_pose(robot, pose)[source]

Moves the robot the the specified pose.

Parameters:
  • robot (Robot) – Robot instance to move.
  • pose (Pose) – Target or goal pose instance.
Returns:

An instance of Configuration found for the given pose.