klampt.model.create package
Utilities for creating primitives, moving base robots, canonical robot models, and stable piles.
Submodules
Common code for creating and moving free-floating moving bases. |
|
Utility functions for making arrangments / piles of objects. |
|
Utilities for creating geometric primitives (and world entities made out of them). |
klampt.model.create.moving_base_robot module
Common code for creating and moving free-floating moving bases.
The way to do this is to add a “virtual linkage” of 3 translational DOFs and 3 revolute DOFs. Some tuning may need to be done to the motor drivers in order to make the controller stable.
- klampt.model.create.moving_base_robot.make(robotfile, world, tempname='temp.rob', debug=False)[source]
Converts the given geometry or fixed-base robot file into a moving base robot and loads it into the given world.
- Return type:
- Parameters:
robotfile (str) – the name of a geometry or fixed-base robot file (.rob or .urdf) to load.
world (WorldModel) – a world that will contain the new robot
tempname (str, optional) – a name of a temporary file containing the moving-base robot
debug (bool, optional) – if True, the robot file named by
tempname
is not removed from disk.
- Returns:
the loaded robot, stored in
world
.- Return type:
- klampt.model.create.moving_base_robot.get_xform(robot)[source]
For a moving base robot model, returns the current base rotation matrix R and translation t.
- Return type:
Tuple
[Sequence
[float
],Sequence
[float
]]
- klampt.model.create.moving_base_robot.set_xform(robot, R, t)[source]
For a moving base robot model, set the current base rotation matrix R and translation t. (Note: if you are controlling a robot during simulation, use send_moving_base_xform_command)
- Return type:
None
- klampt.model.create.moving_base_robot.send_xform_linear(controller, R, t, dt)[source]
For a moving base robot model, send a command to move to the rotation matrix R and translation t using linear interpolation over the duration dt.
Note: with the reflex model, can’t currently set hand commands and linear base commands simultaneously
- Return type:
None
- klampt.model.create.moving_base_robot.send_xform_PID(controller, R, t)[source]
For a moving base robot model, send a command to move to the rotation matrix R and translation t by setting the PID setpoint
Note: with the reflex model, can’t currently set hand commands and linear base commands simultaneously
- Return type:
None
klampt.model.create.pile module
Utility functions for making arrangments / piles of objects.
Main functions are make_object_arrangement()
and
make_object_pile()
.
- klampt.model.create.pile.xy_randomize(obj, bmin, bmax)[source]
Randomizes the xy position and z orientation of an object inside of a bounding box bmin->bmax. Assumes the bounding box is large enough to hold the object in any orientation.
- klampt.model.create.pile.xy_jiggle(world, objects, fixed_objects, bmin, bmax, iters, randomize=True, verbose=0)[source]
Jiggles the objects’ x-y positions within the range bmin - bmax, and randomizes orientation about the z axis until the objects are collision free. A list of fixed objects (fixed_objects) may be given as well.
Objects for which collision-free resolutions are not found are returned.
- klampt.model.create.pile.make_object_arrangement(world, container, objects, container_wall_thickness=0.01, max_iterations=100, remove_failures=False)[source]
For a given container and a list of objects in the world, places the objects inside the container with randomized x-y locations and z orientations so that they are initially collision free and on the bottom of the container.
- Return type:
- Parameters:
world (WorldModel) – the world containing the objects and obstacles
container – the container RigidObjectModel / TerrainModel in world into which objects should be spawned. Assumed axis-aligned.
objects (list of RigidObjectModel) – a list of RigidObjects in the world, at arbitrary locations. They are placed in order.
container_wall_thickness (float, optional) – a margin subtracted from the container’s outer dimensions into which the objects are spawned.
max_iterations (int, optional) – the maximum number of iterations used for sampling object initial poses
remove_failures (bool) – if True, then instead of returning None on failure, the objects that fail placement are removed from the world.
- Returns:
if successful, the positions of objects in world are modified and world is returned. On failure, None is returned.
- Return type:
Note
Since world is modified in-place, if you wish to make multiple worlds with piles of the same objects, you should use world.copy() to store the configuration of the objects. You may also wish to randomize the object ordering using random.shuffle(objects) between instances.
- klampt.model.create.pile.make_object_pile(world, container, objects, container_wall_thickness=0.01, randomize_orientation=True, visualize=False, verbose=0)[source]
For a given container and a list of objects in the world, drops the objects inside the container and simulates until stable.
- Return type:
Tuple
[WorldModel
,Simulator
]- Parameters:
world (WorldModel) – the world containing the objects and obstacles
container – the container RigidObjectModel / TerrainModel in world into which objects should be spawned. Assumed axis-aligned.
objects (list of RigidObjectModel) – a list of RigidObjectModels in the world, at arbitrary locations. They are placed in order.
container_wall_thickness (float, optional) – a margin subtracted from the container’s outer dimensions into which the objects are spawned.
randomize_orientation (bool or str, optional) – if True, the orientation of the objects are completely randomized. If ‘z’, only the z orientation is randomized. If False or None, the orientation is unchanged
visualize (bool, optional) – if True, pops up a visualization window to show the progress of the pile
verbose (int, optional) – if > 0, prints progress of the pile.
- Returns:
A pair (world,sim), containing
world (WorldModel): the original world
- sim (Simulator): the Simulator instance at the state used to obtain
the stable placement of the objects.
Note
If you wish to make multiple worlds with piles of the same objects, you may wish to randomize the object ordering using
random.shuffle(objects)
between instances.
klampt.model.create.primitives module
Utilities for creating geometric primitives (and world entities made out of them).
- klampt.model.create.primitives.box(width, depth, height, center=None, R=None, t=None, world=None, name=None, mass=inf, type='TriangleMesh')[source]
Makes a box with dimensions width x depth x height. The box is centered at (0,0,0) by default.
- Parameters:
width (float) – x,y,z dimensions of the box
depth (float) – x,y,z dimensions of the box
height (float) – x,y,z dimensions of the box
center (list of 3 floats, optional) – if None (typical), the geometry of the box is centered at 0. Otherwise, the geometry of the box is shifted relative to the box’s local coordinate system.
R (se3 transform, optional) – if given, the box’s world coordinates will be rotated and shifted by this transform.
t (se3 transform, optional) – if given, the box’s world coordinates will be rotated and shifted by this transform.
world (WorldModel, optional) – If given, then the box will be a RigidObjectModel or TerrainModel will be created in this world
name (str, optional) – If world is given, this is the name of the object. Default is ‘box’.
mass (float, optional) – If world is given and this is inf, then a TerrainModel will be created. Otherwise, a RigidObjectModel will be created with automatically determined inertia.
type (str, optional) – the geometry type. Defaults to ‘TriangleMesh’, but also ‘GeometricPrimitive’ and ‘VolumeGrid’ are accepted.
- Returns:
A representation of the box. If a world is given, then either a RigidObjectModel or TerrainModel is added to the world and returned.
- Return type:
- klampt.model.create.primitives.sphere(radius, center=None, R=None, t=None, world=None, name=None, mass=inf, resolution=0.0, type='TriangleMesh')[source]
Makes a sphere with the given radius
- Parameters:
radius (float) – radius of the sphere
center (list of 3 floats, optional) – if None (typical), the geometry of the sphere is centered at 0. Otherwise, the geometry of the sphere is shifted relative to the sphere’s local coordinate system.
R (se3 transform, optional) – if given, the sphere’s world coordinates will be rotated and shifted by this transform.
t (se3 transform, optional) – if given, the sphere’s world coordinates will be rotated and shifted by this transform.
world (WorldModel, optional) – If given, then the sphere will be a RigidObjectModel or TerrainModel will be created in this world
name (str, optional) – If world is given, this is the name of the object. Default is ‘sphere’.
mass (float, optional) – If world is given and this is inf, then a TerrainModel will be created. Otherwise, a RigidObjectModel will be created with automatically determined inertia.
resolution (float, optional) – if non-zero, the sphere will be discretized at the given resolution rather than the default.
type (str, optional) – the geometry type. Defaults to ‘TriangleMesh’, but also ‘GeometricPrimitive’ and ‘VolumeGrid’ are accepted.
- Returns:
A representation of the sphere. If a world is given, then either a RigidObjectModel or TerrainModel is added to the world and returned.
- Return type:
- klampt.model.create.primitives.bbox(bmin, bmax, R=None, t=None, world=None, name=None, mass=inf, type='TriangleMesh')[source]
Makes a box from bounds [bmin,bmax].
- Parameters:
bmin (list of 3 floats) – the lower corner of the box
center (list of 3 floats) – the upper corner of the box
R (se3 transform, optional) – if given, the box’s world coordinates will be rotated and shifted by this transform.
t (se3 transform, optional) – if given, the box’s world coordinates will be rotated and shifted by this transform.
world (WorldModel, optional) – If given, then the box will be a RigidObjectModel or TerrainModel will be created in this world
name (str, optional) – If world is given, this is the name of the object. Default is ‘box’.
mass (float, optional) – If world is given and this is inf, then a TerrainModel will be created. Otherwise, a RigidObjectModel will be created with automatically determined inertia.
type (str, optional) – the geometry type. Defaults to ‘TriangleMesh’, but also ‘GeometricPrimitive’ and ‘VolumeGrid’ are accepted.
- Returns:
A representation of the box. If a world is given, then either a RigidObjectModel or TerrainModel is added to the world and returned.
- Return type: