pycram.worlds.multiverse#
Classes#
This class implements an interface between Multiverse and PyCRAM. |
Module Contents#
- class pycram.worlds.multiverse.Multiverse(is_prospection: typing_extensions.Optional[bool] = False, clear_cache: bool = False)#
Bases:
pycram.datastructures.world.WorldThis class implements an interface between Multiverse and PyCRAM.
- conf: pycram.config.multiverse_conf.MultiverseConfig#
The Multiverse configuration.
- supported_joint_types#
A Tuple for the supported pycram joint types in Multiverse.
- added_multiverse_resources: bool = False#
A flag to check if the multiverse resources have been added.
- latest_save_id: typing_extensions.Optional[int] = None#
- saved_simulator_states: typing_extensions.Dict#
- simulation = 'belief_state'#
- client_manager#
- ray_test_utils#
- is_paused: bool = False#
- _init_clients(is_prospection: bool = False)#
Initialize the Multiverse clients that will be used to communicate with the Multiverse server. Each client is responsible for a specific task, e.g. reading data from the server, writing data to the serve,
calling the API, or controlling the robot joints.
- Parameters:
is_prospection – Whether the world is prospection or not.
- _init_constraint_and_object_id_name_map_collections()#
- _init_world(mode: pycram.datastructures.enums.WorldMode)#
- classmethod make_sure_multiverse_resources_are_added(clear_cache: bool = False) None#
Add the multiverse resources to the pycram world resources, and change the data directory and cache manager.
- Parameters:
clear_cache – Whether to clear the cache or not.
- remove_multiverse_resources()#
Remove the multiverse resources from the pycram world resources.
- _spawn_floor()#
Spawn the plane in the simulator.
- pause_simulation() None#
Pause the simulation.
- unpause_simulation() None#
Unpause the simulation.
- load_generic_object_and_get_id(description: pycram.object_descriptors.generic.ObjectDescription, pose: typing_extensions.Optional[pycram.datastructures.pose.PoseStamped] = None) int#
- get_images_for_target(target_pose: pycram.datastructures.pose.PoseStamped, cam_pose: pycram.datastructures.pose.PoseStamped, size: int = 256, camera_min_distance: float = 0.1, camera_max_distance: int = 3, plot: bool = False) typing_extensions.List[numpy.ndarray]#
Uses ray test to get the images for the target object. (target_pose is currently not used)
- static get_joint_position_name(joint: pycram.description.Joint) pycram.datastructures.enums.MultiverseJointPosition#
Get the attribute name of the joint position in the Multiverse from the pycram joint type.
- Parameters:
joint – The joint.
- spawn_robot_with_controller(name: str, pose: pycram.datastructures.pose.PoseStamped) None#
Spawn the robot in the simulator.
- Parameters:
name – The name of the robot.
pose – The pose of the robot.
- load_object_and_get_id(name: typing_extensions.Optional[str] = None, pose: typing_extensions.Optional[pycram.datastructures.pose.PoseStamped] = None, obj_type: typing_extensions.Optional[typing_extensions.Type[pycrap.PhysicalObject]] = None) int#
Spawn the object in the simulator and return the object id. Object name has to be unique and has to be same as the name of the object in the description file.
- Parameters:
name – The name of the object to be loaded.
pose – The pose of the object.
obj_type – The type of the object.
- spawn_object(name: str, object_type: typing_extensions.Type[pycrap.PhysicalObject], pose: pycram.datastructures.pose.PoseStamped) None#
Spawn the object in the simulator.
- Parameters:
name – The name of the object.
object_type – The type of the object.
pose – The pose of the object.
- spawn_robot(name: str, pose: pycram.datastructures.pose.PoseStamped) None#
Spawn the robot in the simulator.
- Parameters:
name – The name of the robot.
pose – The pose of the robot.
- _update_object_id_name_maps_and_get_latest_id(name: str) int#
Update the object id name maps and return the latest object id.
- Parameters:
name – The name of the object.
- Returns:
The latest object id.
- get_object_joint_names(obj: pycram.world_concepts.world_object.Object) typing_extensions.List[str]#
- get_object_link_names(obj: pycram.world_concepts.world_object.Object) typing_extensions.List[str]#
- get_link_position(link: pycram.description.Link) typing_extensions.List[float]#
- get_link_orientation(link: pycram.description.Link) typing_extensions.List[float]#
- get_multiple_link_positions(links: typing_extensions.List[pycram.description.Link]) typing_extensions.Dict[str, typing_extensions.List[float]]#
- get_multiple_link_orientations(links: typing_extensions.List[pycram.description.Link]) typing_extensions.Dict[str, typing_extensions.List[float]]#
- _reset_joint_position(joint: pycram.description.Joint, joint_position: float) bool#
- _reset_joint_position_using_controller(joint: pycram.description.Joint, joint_position: float) bool#
Reset the position of a joint in the simulator using the controller.
- Parameters:
joint – The joint.
joint_position – The position of the joint.
- Returns:
True if the joint position is reset successfully.
- _set_multiple_joint_positions(joint_positions: typing_extensions.Dict[pycram.description.Joint, float]) bool#
Set the positions of multiple joints in the simulator. Also check if the joint is controlled by an actuator and use the controller to set the joint position if the joint is controlled.
- Parameters:
joint_positions – The dictionary of joints and positions.
- Returns:
True if the joint positions are set successfully (this means that the joint positions are set without errors, but not necessarily that the joint positions are set to the specified values).
- get_controlled_joints(joints: typing_extensions.Optional[typing_extensions.List[pycram.description.Joint]] = None) typing_extensions.List[pycram.description.Joint]#
Get the joints that are controlled by an actuator from the list of joints.
- Parameters:
joints – The list of joints to check.
- Returns:
The list of controlled joints.
- _set_multiple_joint_positions_without_controller(joint_positions: typing_extensions.Dict[pycram.description.Joint, float]) None#
Set the positions of multiple joints in the simulator without using the controller.
- Parameters:
joint_positions – The dictionary of joints and positions.
- _set_multiple_joint_positions_using_controller(joint_positions: typing_extensions.Dict[pycram.description.Joint, float]) bool#
Set the positions of multiple joints in the simulator using the controller.
- Parameters:
joint_positions – The dictionary of joints and positions.
- _get_joint_position(joint: pycram.description.Joint) typing_extensions.Optional[float]#
- _get_multiple_joint_positions(joints: typing_extensions.List[pycram.description.Joint]) typing_extensions.Optional[typing_extensions.Dict[str, float]]#
- static get_joint_cmd_name(joint_type: pycram.datastructures.enums.JointType) pycram.datastructures.enums.MultiverseJointCMD#
Get the attribute name of the joint command in the Multiverse from the pycram joint type.
- Parameters:
joint_type – The pycram joint type.
- get_link_pose(link: pycram.description.Link) typing_extensions.Optional[pycram.datastructures.pose.PoseStamped]#
- get_multiple_link_poses(links: typing_extensions.List[pycram.description.Link]) typing_extensions.Dict[str, pycram.datastructures.pose.PoseStamped]#
- get_object_pose(obj: pycram.world_concepts.world_object.Object) pycram.datastructures.pose.PoseStamped#
- get_multiple_object_poses(objects: typing_extensions.List[pycram.world_concepts.world_object.Object]) typing_extensions.Dict[str, pycram.datastructures.pose.PoseStamped]#
Set the poses of multiple objects in the simulator. If the object is of type environment, the pose will be the default pose.
- Parameters:
objects – The list of objects.
- Returns:
The dictionary of object names and poses.
- reset_object_base_pose(obj: pycram.world_concepts.world_object.Object, pose: pycram.datastructures.pose.PoseStamped) bool#
- reset_multiple_objects_base_poses(objects: typing_extensions.Dict[pycram.world_concepts.world_object.Object, pycram.datastructures.pose.PoseStamped]) None#
Reset the poses of multiple objects in the simulator.
- Parameters:
objects – The dictionary of objects and poses.
- _set_body_pose(body_name: str, pose: pycram.datastructures.pose.PoseStamped) None#
Reset the pose of a body (object, link, or joint) in the simulator.
- Parameters:
body_name – The name of the body.
pose – The pose of the body.
- _set_multiple_body_poses(body_poses: typing_extensions.Dict[str, pycram.datastructures.pose.PoseStamped]) None#
Reset the poses of multiple bodies in the simulator.
- Parameters:
body_poses – The dictionary of body names and poses.
- _get_body_pose(body_name: str, wait: typing_extensions.Optional[bool] = True) typing_extensions.Optional[pycram.datastructures.pose.PoseStamped]#
Get the pose of a body in the simulator.
- Parameters:
body_name – The name of the body.
wait – Whether to wait until the pose is received.
- Returns:
The pose of the body.
- _get_multiple_body_poses(body_names: typing_extensions.List[str]) typing_extensions.Dict[str, pycram.datastructures.pose.PoseStamped]#
Get the poses of multiple bodies in the simulator.
- Parameters:
body_names – The list of body names.
- get_multiple_object_positions(objects: typing_extensions.List[pycram.world_concepts.world_object.Object]) typing_extensions.Dict[str, typing_extensions.List[float]]#
- get_object_position(obj: pycram.world_concepts.world_object.Object) typing_extensions.List[float]#
- get_multiple_object_orientations(objects: typing_extensions.List[pycram.world_concepts.world_object.Object]) typing_extensions.Dict[str, typing_extensions.List[float]]#
- get_object_orientation(obj: pycram.world_concepts.world_object.Object) typing_extensions.List[float]#
- multiverse_reset_world()#
Reset the world using the Multiverse API.
- disconnect_from_physics_server() None#
- join_threads() None#
- _remove_visual_object(obj_id: int) bool#
- remove_object_from_simulator(obj: pycram.world_concepts.world_object.Object) bool#
- add_constraint(constraint: pycram.world_concepts.constraints.Constraint) int#
- _update_constraint_collection_and_get_latest_id(constraint: pycram.world_concepts.constraints.Constraint) int#
Update the constraint collection and return the latest constraint id.
- Parameters:
constraint – The constraint to be added.
- Returns:
The latest constraint id.
- remove_constraint(constraint_id) None#
- perform_collision_detection() None#
- get_body_contact_points(body: pycram.datastructures.world_entity.PhysicalBody) pycram.datastructures.dataclasses.ContactPointsList#
- get_object_contact_points(obj: pycram.world_concepts.world_object.Object, ignore_attached_objects: bool = True) pycram.datastructures.dataclasses.ContactPointsList#
Note: Currently Multiverse only gets one contact point per contact objects.
- Parameters:
obj – The object.
ignore_attached_objects – Whether to ignore the attached objects or not.
- Returns:
The contact points of the object.
- get_object_with_body_name(body_name: str) typing_extensions.Tuple[typing_extensions.Optional[pycram.world_concepts.world_object.Object], typing_extensions.Optional[pycram.description.Link]]#
Get the object with the body name in the simulator, the body name can be the name of the object or the link.
- Parameters:
body_name – The name of the body.
- Returns:
The object if found otherwise None, and the link if the body name is a link.
- static _get_normal_force_on_object_from_contact_force(obj: pycram.world_concepts.world_object.Object, contact_force: typing_extensions.List[float]) float#
Get the normal force on an object from the contact force exerted by another object that is expressed in the world frame. Thus transforming the contact force to the object frame is necessary.
- Parameters:
obj – The object.
contact_force – The contact force.
- Returns:
The normal force on the object.
- get_contact_points_between_two_bodies(obj1: pycram.world_concepts.world_object.Object, obj2: pycram.world_concepts.world_object.Object) pycram.datastructures.dataclasses.ContactPointsList#
- _ray_test(from_position: typing_extensions.List[float], to_position: typing_extensions.List[float]) pycram.datastructures.dataclasses.RayResult#
- _ray_test_batch(from_positions: typing_extensions.List[typing_extensions.List[float]], to_positions: typing_extensions.List[typing_extensions.List[float]], num_threads: int = 1, return_distance: bool = False) typing_extensions.List[pycram.datastructures.dataclasses.RayResult]#
Note: Currently, num_threads is not used in Multiverse.
- step(func: typing_extensions.Optional[typing_extensions.Callable[[], None]] = None, step_seconds: typing_extensions.Optional[float] = None) None#
Perform a simulation step in the simulator, this is useful when use_static_mode is True.
- Parameters:
func – A function to be called after the simulation step.
step_seconds – The number of seconds to step the simulation.
- save_physics_simulator_state(state_id: typing_extensions.Optional[int] = None, use_same_id: bool = False) int#
- remove_physics_simulator_state(state_id: int) None#
- restore_physics_simulator_state(state_id: int) None#
- set_link_color(link: pycram.description.Link, rgba_color: pycram.datastructures.dataclasses.Color)#
- get_link_color(link: pycram.description.Link) pycram.datastructures.dataclasses.Color#
- get_colors_of_object_links(obj: pycram.world_concepts.world_object.Object) typing_extensions.Dict[str, pycram.datastructures.dataclasses.Color]#
- set_realtime(real_time: bool) None#
- set_gravity(gravity_vector: typing_extensions.List[float]) None#
- check_object_exists(obj: pycram.world_concepts.world_object.Object) bool#
Check if the object exists in the Multiverse world.
- Parameters:
obj – The object.
- Returns:
True if the object exists, False otherwise.