intrinsic.solutions.worlds.ObjectWorld
![]() View source on GitHub |
Extends an ObjectWorldClient with a connect method.
Inherits From: ObjectWorldClient
intrinsic.solutions.worlds.ObjectWorld(
world_id: str,
stub: intrinsic.solutions.simulation.ObjectWorldServiceStub,
geometry_service_stub: Optional[geometry_service_pb2_grpc.GeometryServiceStub] = None
)
Attributes | |
|---|---|
Returns the gRPC stub. | |
Methods
batch_update
View source
batch_update(
updates: object_world_updates_pb2.ObjectWorldUpdates
) -> None
Processes a number of world updates all at once.
| Arguments | |
|---|---|
| The set of updates to apply. |
connect
View source
@classmethodconnect( world_id: str, grpc_channel: grpc.Channel ) -> 'ObjectWorldExternal'
create_frame
View source
create_frame(
frame_name: intrinsic.world.python.object_world_ids.FrameName,
parent: Optional[intrinsic.world.python.object_world_resources.TransformNode] = None,
parent_t_frame: Optional[intrinsic.math.python.data_types.Pose3] = data_types.Pose3()
) -> intrinsic.world.python.object_world_resources.Frame
Creates a new frame in the world.
| Arguments | |
|---|---|
| The name of the new frame. Must be unique amongst all frames under the same object. |
| The object or frame under which the new frame shall be created. Default is the root object. |
| The transform between the parent and the new frame. Default is a identity transform. |
| Returns | |
|---|---|
The created frame. |
create_geometry_object
View source
create_geometry_object(
*,
object_name: intrinsic.world.python.object_world_ids.WorldObjectName,
geometry_component: geometry_component_pb2.GeometryComponent,
parent: Optional[intrinsic.world.python.object_world_resources.WorldObject] = None,
parent_object_t_created_object: intrinsic.math.python.data_types.Pose3 = data_types.Pose3()
) -> None
Adds a geometry object to the world.
| Arguments | |
|---|---|
| The name of the newly created object. |
| Geometry information for the object to be added. |
| The parent object the new object will be attached to. |
| The transform between the parent object and the new object. |
create_object_from_product_part
View source
create_object_from_product_part(
*,
part: ppr.ProductPart,
object_name: intrinsic.world.python.object_world_ids.WorldObjectName,
parent: Optional[intrinsic.world.python.object_world_resources.WorldObject] = None,
parent_object_t_created_object: Optional[intrinsic.math.python.data_types.Pose3] = data_types.Pose3()
) -> None
Adds a product part as object to the world.
| Arguments | |
|---|---|
| The ProductPart to add. |
| The name of the newly created object. |
| The parent object the new product object will be attached to. |
| The transform between the parent object and the new product object. |
delete_frame
View source
delete_frame(
frame: intrinsic.world.python.object_world_resources.Frame,
*,
force: bool = False
) -> None
Deletes a frame.
| Arguments | |
|---|---|
| The frame to delete. |
| Enables force deletion to remove frames including their children. |
delete_object
View source
delete_object(
world_object: intrinsic.world.python.object_world_resources.WorldObject,
*,
force: bool = False
) -> None
Deletes an object.
| Arguments | |
|---|---|
| The object to delete. |
| Enables force deletion to remove objects including their children. |
disable_collisions
View source
disable_collisions(
first_object: intrinsic.world.python.object_world_resources.WorldObject,
second_object: intrinsic.world.python.object_world_resources.WorldObject,
*,
first_entity_filter: object_world_refs_pb2.ObjectEntityFilter = intrinsic.world.python.object_world_client.INCLUDE_ALL_ENTITIES,
second_entity_filter: object_world_refs_pb2.ObjectEntityFilter = intrinsic.world.python.object_world_client.INCLUDE_ALL_ENTITIES
) -> None
Disables collisions between two objects.
Disables collision detection between all pairs (a, b) of entities where a is a entity of 'object_a' and selected by 'entity_filter_a' and b is an entity of 'object_b' and selected by 'entity_filter_b'.
Succeeds and has no effect if collisions were already disabled.
| Args | |
|---|---|
| The first object. |
| The second object. |
| Entity filter for the first object. By default all object entities will be included. |
| Entity filter for the second object. By default all object entities will be included. |
enable_collisions
View source
enable_collisions(
first_object: intrinsic.world.python.object_world_resources.WorldObject,
second_object: intrinsic.world.python.object_world_resources.WorldObject,
*,
first_entity_filter: object_world_refs_pb2.ObjectEntityFilter = intrinsic.world.python.object_world_client.INCLUDE_ALL_ENTITIES,
second_entity_filter: object_world_refs_pb2.ObjectEntityFilter = intrinsic.world.python.object_world_client.INCLUDE_ALL_ENTITIES
) -> None
Enables collisions between two objects.
Enables collision detection between all pairs (a, b) of entities where a is an entity of 'object_a' and selected by 'entity_filter_a' and b is an entity of 'object_b' and selected by 'entity_filter_b'.
Succeeds and has no effect if collisions were already enabled.
| Args | |
|---|---|
| The first object. |
| The second object. |
| Entity filter for the first object. By default all object entities will be included. |
| Entity filter for the second object. By default all object entities will be included. |
get_frame
View source
get_frame(
frame_reference: Union[object_world_refs_pb2.FrameReference, intrinsic.world.python.object_world_ids.FrameName],
object_name: Optional[Union[object_world_ids.WorldObjectName, resource_handle_pb2.
ResourceHandle]] = None
) -> intrinsic.world.python.object_world_resources.Frame
Returns a frame by its reference.
This method accepts a FrameReference or the names of frame and parent object as argument. Expected uses look like:
world.get_frame(object_world_ids.FrameName('my_frame'), object_world_ids.WorldObjectName('my_object'))
world.get_frame(object_world_refs_pb2.FrameReference( by_name=object_world_refs_pb2.FrameReferenceByName( frame_name='my_frame', object_name='my_object')))
Note, if you provide an object by its resource handle, then the frame must be referenced by the frame's name.
Only in Jupyter does it also work with normal strings:
world.get_frame('my_frame', 'my_object')
| Args | |
|---|---|
| A reference to the requested frame. |
| The optional reference to the frames parent object. |
| Returns | |
|---|---|
The frame in the world. |
get_kinematic_object
View source
get_kinematic_object(
object_reference: Union[object_world_ids.WorldObjectName, object_world_refs_pb2.
ObjectReference, resource_handle_pb2.ResourceHandle]
) -> intrinsic.world.python.object_world_resources.KinematicObject
Returns a kinematic object by its unique name.
| Args | |
|---|---|
| The name of the object, a reference to the object or the name of the equipment associated with the object. |
| Returns | |
|---|---|
A kinematic object in the world. |
| Raises | |
|---|---|
| The requested object has no kinematic component and cannot be used as kinematic object. |
get_object
View source
get_object(
object_reference: Union[object_world_ids.WorldObjectName, object_world_refs_pb2.
ObjectReference, resource_handle_pb2.ResourceHandle]
) -> intrinsic.world.python.object_world_resources.WorldObject
Returns an object by its unique name.
| Args | |
|---|---|
| The name or reference of the object. |
| Returns | |
|---|---|
An object in the world as an instance of WorldObject or a subclass thereof. |
get_transform
View source
get_transform(
node_a: intrinsic.world.python.object_world_resources.TransformNode,
node_b: intrinsic.world.python.object_world_resources.TransformNode
) -> intrinsic.math.python.data_types.Pose3
Get the transform between two nodes in the world.
| Args | |
|---|---|
| The first transform node. |
| the second transform node. |
| Returns | |
|---|---|
The transform 'a_t_b', i.e., the pose of 'node_b' in the space of 'node_a'. 'node_a' and 'node_b' can be arbitrary nodes in the transform tree of the world and don't have to be parent and child. |
get_transform_node
View source
get_transform_node(
reference: Union[object_world_ids.ObjectWorldResourceId, object_world_refs_pb2.
TransformNodeReference]
) -> intrinsic.world.python.object_world_resources.TransformNode
Returns a transform node (object or frame).
| Args | |
|---|---|
| The id of the transform node or a reference (by id or name) to the transform node. |
| Returns | |
|---|---|
The transform node in the world. Either a Frame or a subclass of WorldObject. |
list_object_full_paths
View source
list_object_full_paths() -> List[str]
Lists the full path names of all objects from the world namespace.
| Returns | |
|---|---|
A list with the fully qualified names of all objects in the world. E.g. ['robot', 'robot.gripper', 'robot.gripper.workpiece', 'workcell'] |
list_object_names
View source
list_object_names() -> List[intrinsic.world.python.object_world_ids.WorldObjectName]
Lists the names of all objects in the world service.
| Returns | |
|---|---|
A list with the names of all objects in the world. |
list_objects
View source
list_objects() -> List[intrinsic.world.python.object_world_resources.WorldObject]
List all objects in the world service.
| Returns | |
|---|---|
A list with all objects in the world. |
register_geometry
View source
register_geometry(
*, geometry: geometry_service_pb2.CreateGeometryRequest
) -> geometry_storage_refs_pb2.GeometryStorageRefs
Registers geometry so that it can be referenced to create an object.
| Arguments | |
|---|---|
| Geometry data to be registered. |
| Raises | |
|---|---|
| if ObjectWorldClient was not configured with the geometry service client. |
| Returns | |
|---|---|
Opaque references corresponding to the registered geometry. |
reparent_frame
View source
reparent_frame(
frame: intrinsic.world.python.object_world_resources.Frame,
parent: intrinsic.world.python.object_world_resources.TransformNode
) -> None
Re-parent an existing frame in the world to another frame or object.
| Arguments | |
|---|---|
| The frame you want to reparent. |
| The object or frame under which the new frame shall be moved. If parent type is WorldObject, the frame will attach to the final entity. |
reparent_object
View source
reparent_object(
child_object: intrinsic.world.python.object_world_resources.WorldObject,
new_parent: intrinsic.world.python.object_world_resources.WorldObject
) -> None
Reparents an object to a new parent object.
Leaves the global pose of the reparented object unaffected (i.e., "parent_t_object" might change but "root_t_object" will not change).
If the new parent object is a kinematic object, this method attaches the child object to the parent's base object entity (also see reparent_object_to_final_entity()).
| Args | |
|---|---|
| The object that should be reparented. |
| The new parent object. |
reparent_object_to
View source
reparent_object_to(
child_object: intrinsic.world.python.object_world_resources.WorldObject,
new_parent: intrinsic.world.python.object_world_resources.WorldObject,
entity_filter: object_world_refs_pb2.ObjectEntityFilter
) -> None
Reparents an object to a new parent object.
Leaves the global pose of the reparented object unaffected (i.e., "parent_t_object" might change but "root_t_object" will not change).
This method attaches the child object to the parent's object entity that matches the given filter.
| Args | |
|---|---|
| The object that should be reparented. |
| The new parent object. |
| The object entity filter. |
reparent_object_to_final_entity
View source
reparent_object_to_final_entity(
child_object: intrinsic.world.python.object_world_resources.WorldObject,
new_parent: intrinsic.world.python.object_world_resources.KinematicObject
) -> None
Reparents an object to the final entity of a kinematic object.
Leaves the global pose of the reparented object unaffected (i.e., "parent_t_object" might change but "root_t_object" will not change).
If a final entity of the new parent object cannot be determined uniquely, an error will be returned.
| Args | |
|---|---|
| The object that should be reparented. |
| The new parent object, which must be a kinematic object. |
reset
View source
reset() -> None
Restores the initial world from the world service.
Overrides the current belief world.
update_frame_name
View source
update_frame_name(
frame_to_update: intrinsic.world.python.object_world_resources.Frame,
new_name: intrinsic.world.python.object_world_ids.FrameName
) -> None
Changes the name of the given frame to the given name.
| Args | |
|---|---|
| The frame that should be updated. |
| The name of the new frame. |
| Raises | |
|---|---|
| The new name is already used for another frame under the same object. |
update_joint_application_limits
View source
update_joint_application_limits(
kinematic_object: intrinsic.world.python.object_world_resources.KinematicObject,
joint_limits: joint_limits_pb2.JointLimitsUpdate
) -> None
Sets the joint application limits of the kinematic object to the given values.
| Args | |
|---|---|
| The kinematic object that should be changed. |
| The new joint limits. The field JointLimits.max_effort is currently not supported and will be ignored. |
update_joint_positions
View source
update_joint_positions(
kinematic_object: intrinsic.world.python.object_world_resources.KinematicObject,
joint_positions: List[float],
joint_names: Optional[List[str]] = None
) -> None
Sets the joint positions of the kinematic object to the given values.
| Args | |
|---|---|
| The kinematic object that should be changed. |
| The new joint positions in radians (for revolute joints) or meters (for prismatic joints). |
| Optional joint names to correspond to the given joint_positions must either be empty or match the size of the joint_positions list. |
update_joint_system_limits
View source
update_joint_system_limits(
kinematic_object: intrinsic.world.python.object_world_resources.KinematicObject,
joint_limits: joint_limits_pb2.JointLimitsUpdate
) -> None
Sets the joint system limits of the kinematic object to the given values.
| Args | |
|---|---|
| The kinematic object that should be changed. |
| The new joint system limits. The field JointLimits.max_effort is currently not supported and will be ignored. |
update_kinematic_object_cartesian_limits
View source
update_kinematic_object_cartesian_limits(
kinematic_object: intrinsic.world.python.object_world_resources.KinematicObject,
limits: cart_space_pb2.CartesianLimits
) -> None
Sets the cartesian limits of the kinematic object to the given values.
| Args | |
|---|---|
| The kinematic object that should be changed. |
| The new cartesian limits. |
update_kinematic_object_payload
View source
update_kinematic_object_payload(
kinematic_object: intrinsic.world.python.object_world_resources.KinematicObject,
payload: robot_payload.RobotPayload
) -> None
update_object_name
View source
update_object_name(
object_to_update: intrinsic.world.python.object_world_resources.WorldObject,
new_name: intrinsic.world.python.object_world_ids.WorldObjectName,
*,
name_is_global_alias: bool = True
) -> None
Changes the name of the given object to the given name.
| Args | |
|---|---|
| The object that should be updated. |
| The new name of the object. |
| If True, new_name is globally unique. If False, new_name is only unique in its namespace |
| Raises | |
|---|---|
| The new name is already used for another object. |
update_transform
View source
update_transform(
node_a: intrinsic.world.python.object_world_resources.TransformNode,
node_b: intrinsic.world.python.object_world_resources.TransformNode,
a_t_b: intrinsic.math.python.data_types.Pose3,
node_to_update: Optional[intrinsic.world.python.object_world_resources.TransformNode] = None
) -> None
Updates the pose between two nodes.
If node_to_update is None this updates the pose between two neighboring nodes 'node_a' and 'node_b' such that the transform between the two becomes 'a_t_b'. If 'node_b' is the direct child of 'node_a', 'node_b.parent_t_this' is updated; if 'node_a' is the direct child of 'node_b', 'node_a.parent_t_this' is updated; otherwise, an error will be returned.
If node_to_update is not None this updates the pose of the given 'node_to_update' in the space of its parent (i.e., 'node_to_update.parent_t_this') such that the transform between 'node_a' and 'node_b' becomes 'a_t_b'. Returns an error if 'node_to_update' is not located on the path from 'node_a' to 'node_b'. It is valid to set 'node_a'=='node_to_update' or 'node_b'=='node_to_update'.
| Args | |
|---|---|
| First transform node. |
| The second transform node. |
| The desired transform between the two nodes 'node_a' and 'node_b'. |
| Optional transform node whose pose (between itself and its parent) shall be updated. Can be left out if 'node_a' and 'node_b' are neighbors in the transform tree, then the pose of the child node will be updated. |
| Raises | |
|---|---|
| Error communicating with the world service. |
