klampt.model.workspace module

Functions for computing robot workspaces, with lots of options for setting feasibility conditions.

New in version 0.9.

klampt.model.workspace.compute_occupancy_grid(points, resolution=0.05, dimensions=None, bounds=None, value='occupancy')[source]

Helper to compute an occupancy grid given a set of points.

Return type:

VolumeGrid

Parameters:
  • points (list of Vector3 or nx3 array) – the points

  • resolution (float, 3-vector, or None) – the resolution of the resulting grid.

  • dimensions (int or 3-vector optional) – if resolution=None and dimensions is given, the number of dimensions. If a single int, the cell size is determined by dividing the longest side by dimensions.

  • bounds (pair of 3-vectors, optional) – specifies the minimum and maximum range of the grid. If not given, calculated by the

  • value (str) – either ‘occupancy’, ‘count’, or ‘probability’.

klampt.model.workspace.compute_field_grid(points, values, resolution=0.05, dimensions=None, bounds=None, aggregator='max', initial_value='auto')[source]

Helper to compute a gridded value field over a set of scattered points.

Return type:

VolumeGrid

Parameters:
  • points (list of Vector3 or nx3 array) – the points

  • values (list of float) – the values at each point

  • resolution (float, 3-vector, or None) – the resolution of the resulting grid.

  • dimensions (int or 3-vector optional) – if resolution=None and dimensions is given, the number of dimensions. If a single int, the cell size is determined by dividing the longest side by dimensions.

  • bounds (pair of 3-vectors, optional) – specifies the minimum and maximum range of the grid. If not given, calculated by the

  • aggregator (str or pair) – either ‘max’, ‘min’, ‘sum’, ‘average’, or a pair of functions (f,g) giving an arbitrary aggregator f(x,value) -> x’, g(x) -> float. x is an arbitrary object, which for each cell is initialized to the value specified by initial_value (default None).

  • initial_value (float or 'auto') – the initial value of the cell before aggregation. If aggregator is a pair of functions, ‘auto’ sets x to None by default.

klampt.model.workspace.compute_workspace(link, constraint_or_point, Nsamples=100000, resolution=0.05, dimensions=None, fixed_links=None, qmin=None, qmax=None, obstacles=None, load=None, load_type=None, gravity=(0, 0, -9.8), self_collision=True, feasibility_test=None, value='occupancy', all_tests=True)[source]

Compute the reachable workspace of a point on a robot’s end effector. Has several options to ensure various feasibility conditions. Ensures that the robot does not collide with itself, optionally with obstacles.

Return type:

Union[VolumeGrid, Dict[str, VolumeGrid]]

Parameters:
  • link (RobotModelLink) – the link on the robot for which the workspace should be computed

  • constraint_or_point (3-vector or IKObjective) – the point on the link. For fixed orientations, use an IKObjective.

  • Nsamples (int) – the number of configuration samples to use

  • resolution (float, 3-vector, or None) – the resolution of the resulting grid.

  • dimensions (int or 3-vector optional) – if resolution=None and dimensions is given, the number of dimensions. If a single int, the cell size is determined by dividing the longest side by dimensions.

  • fixed_links (list of int or str, optional) – list of fixed link indices

  • qmin (Config, optional) – overrides the robots lower joint limits

  • qmax (Config, optional) – overrides the robots upper joint limits

  • obstacles (list of RigidObjectModel or TerrainModel) – Ensures that the robot is collision free with environment obstacles

  • load (float or vector, optional) – a required load capacity, either an isotropic load or a specific vector

  • load_type (str, optional) – either ‘auto’ (default), ‘isotropic’, ‘force’, ‘torque’, ‘wrench’, ‘force_local’, ‘torque_local’, or ‘wrench_local’.

  • gravity (3-vector, optional) – if load testing is used, the gravity vector used for gravity compensation.

  • self_collision (bool) – whether self collision should be tested.

  • feasibility_test (callable, list, or dict) – a function feasible(q)->bool that tests whether the configuration is feasible. If a list, a list of callables. If a dict, a map of str->callable.

  • value (str) – either ‘occupancy’, ‘count’, or ‘probability’.

  • all_tests (bool) – whether to return a dict of results.

Returns:

The grid of reached points. If all_tests=True, gives a set of grids of reached points indexed by strings. Key ‘workspace’ gives the reachable workspace of points meeting every feasibility condition. Keys ‘self_collision_free’, ‘obstacle_X_collision_free’ (X in range 0,…,len(obstacles)-1), ‘load’, ‘feasibility_test’ give the set of points passing each feasibility condition.

klampt.model.workspace.compute_workspace_field(link, constraint_or_point, value, Nsamples=100000, resolution=0.05, dimensions=None, fixed_links=None, qmin=None, qmax=None, obstacles=None, load=None, load_type=None, gravity=(0, 0, -9.8), self_collision=True, feasibility_test=None)[source]

Compute a scalar field over the reachable workspace of a point on a robot’s end effector. Has several options to ensure various feasibility conditions. Ensures that the robot does not collide with itself, optionally with obstacles.

Return type:

VolumeGrid

Parameters:
  • link (RobotModelLink) – the link on the robot for which the workspace should be computed

  • constraint_or_point (3-vector or IKObjective) – the point on the link. For fixed orientations, use an IKObjective.

  • value (str or callable) – ‘occupancy’, ‘manipulability’, ‘max manipulability’, ‘min manipulability’, ‘load’, or an arbitrary function f(q) -> float.

  • Nsamples (int) – the number of configuration samples to use

  • resolution (float, 3-vector, or None) – the resolution of the resulting grid.

  • dimensions (int or 3-vector optional) – if resolution=None and dimensions is given, the number of dimensions. If a single int, the cell size is determined by dividing the longest side by dimensions.

  • fixed_links (list of int or str, optional) – list of fixed link indices

  • qmin (Config, optional) – overrides the robots lower joint limits

  • qmax (Config, optional) – overrides the robots upper joint limits

  • obstacles (list of RigidObjectModel or TerrainModel) – Ensures that the robot is collision free with environment obstacles

  • load (float or vector, optional) – a required load capacity, either an isotropic load or a specific vector

  • load_type (str, optional) – either ‘auto’ (default), ‘isotropic’, ‘force’, ‘torque’, ‘wrench’, ‘force_local’, ‘torque_local’, or ‘wrench_local’.

  • gravity (3-vector, optional) – if load testing is used, the gravity vector used for gravity compensation.

  • self_collision (bool) – whether self collision should be tested.

  • feasibility_test (callable, list, or dict) – a function feasible(q)->bool that tests whether the configuration is feasible. If a list, a list of callables. If a dict, a map of str->callable.

Returns:

The grid of reached points. If all_tests=True, gives a set of grids of reached points. Key ‘workspace’ gives the reachable workspace of points meeting every feasibility condition. Keys ‘self_collision_free’, ‘obstacle_X_collision_free’ (X in range 0,…,len(obstacles)-1), ‘load’, ‘feasibility_test’ give the set of points passing each feasibility condition.