Environments
Module containing the environment interface for HoloOcean. An environment contains all elements required to communicate with a world binary or HoloOceanCore editor.
It specifies an environment, which contains a number of agents, and the interface for communicating with the agents.
Classes:
|
Proxy for communicating with a HoloOcean world |
- class holoocean.environments.HoloOceanEnvironment(agent_definitions=None, binary_path=None, window_size=None, start_world=True, uuid='', gl_version=4, verbose=False, pre_start_steps=2, show_viewport=True, ticks_per_sec=None, frames_per_sec=None, copy_state=True, scenario=None)
Proxy for communicating with a HoloOcean world
Instantiate this object using
holoocean.holoocean.make()
.- Parameters
agent_definitions (
list
ofAgentDefinition
) – Which agents are already in the environmentbinary_path (
str
, optional) – The path to the binary to load the world from. Defaults to None.window_size ((
int
,:obj:int)) – height, width of the window to openstart_world (
bool
, optional) – Whether to load a binary or not. Defaults to True.uuid (
str
) – A unique identifier, used when running multiple instances of holoocean. Defaults to “”.gl_version (
int
, optional) – The version of OpenGL to use for Linux. Defaults to 4.verbose (
bool
) – If engine log output should be printed to stdoutpre_start_steps (
int
) –- Number of ticks to call after initializing the world, allows the
level to load and settle.
show_viewport (
bool
, optional) – If the viewport should be shown (Linux only) Defaults to True.ticks_per_sec (
int
, optional) – The number of frame ticks per unreal seconds. This will override whatever is in the configuration json. Defaults to 30.frames_per_sec (
int
orbool
, optional) – The max number of frames ticks per real seconds. This will override whatever is in the configuration json. If True, will match ticks_per_sec. If False, will not be turned on. If an integer, will set to that value. Defaults to true.copy_state (
bool
, optional) – If the state should be copied or returned as a reference. Defaults to True.scenario (
dict
) – The scenario that is to be loaded. See Scenario File Format for the schema.
Methods:
act
(agent_name, action)Supplies an action to a particular agent, but doesn't tick the environment.
add_agent
(agent_def[, is_main_agent])Add an agent in the world.
draw_arrow
(start, end[, color, thickness])Draws a debug arrow in the world
draw_box
(center, extent[, color, thickness])Draws a debug box in the world
draw_line
(start, end[, color, thickness])Draws a debug line in the world
draw_point
(loc[, color, thickness])Draws a debug point in the world
get_joint_constraints
(agent_name, joint_name)Returns the corresponding swing1, swing2 and twist limit values for the
info
()Returns a string with specific information about the environment.
move_viewport
(location, rotation)Teleport the camera to the given location
publish
(state)Publishes current state to channels chosen by the scenario config.
reset
()Resets the environment, and returns the state.
send_acoustic_message
(id_from, id_to, ...)Send a message from one beacon to another.
send_optical_message
(id_from, id_to, msg_data)Sends data between various instances of OpticalModemSensor
send_world_command
(name[, num_params, ...])Send a world command.
set_control_scheme
(agent_name, control_scheme)Set the control scheme for a specific agent.
set_render_quality
(render_quality)Adjusts the rendering quality of HoloOcean.
should_render_viewport
(render_viewport)Controls whether the viewport is rendered or not
spawn_prop
(prop_type[, location, rotation, ...])Spawns a basic prop object in the world like a box or sphere.
step
(action[, ticks, publish])Supplies an action to the main agent and tells the environment to tick once.
tick
([num_ticks, publish])Ticks the environment once.
Attributes:
Gives the action space for the main agent.
Gets all instances of AcousticBeaconSensor in the environment.
Gets all ids of AcousticBeaconSensor in the environment.
Gets all status of AcousticBeaconSensor in the environment.
Gets all instances of OpticalModemSensor in the environment.
Gets all ids of OpticalModemSensor in the environment.
- act(agent_name, action)
- Supplies an action to a particular agent, but doesn’t tick the environment.
Primary mode of interaction for multi-agent environments. After all agent commands are supplied, they can be applied with a call to tick.
- Parameters
agent_name (
str
) – The name of the agent to supply an action for.action (
np.ndarray
orlist
) – The action to apply to the agent. This action will be applied every time tick is called, until a new action is supplied with another call to act.
- property action_space
Gives the action space for the main agent.
- Returns
The action space for the main agent.
- Return type
- add_agent(agent_def, is_main_agent=False)
Add an agent in the world.
It will be spawn when
tick()
orstep()
is called next.The agent won’t be able to be used until the next frame.
- Parameters
agent_def (
AgentDefinition
) – The definition of the agent tospawn. –
- property beacons
Gets all instances of AcousticBeaconSensor in the environment.
- Returns
List of all AcousticBeaconSensor in environment
- Return type
(
list
ofAcousticBeaconSensor
)
- property beacons_id
Gets all ids of AcousticBeaconSensor in the environment.
- Returns
List of all AcousticBeaconSensor ids in environment
- Return type
(
list
ofint
)
- property beacons_status
Gets all status of AcousticBeaconSensor in the environment.
- Returns
List of all AcousticBeaconSensor status in environment
- Return type
(
list
ofstr
)
- draw_arrow(start, end, color=None, thickness=10.0)
Draws a debug arrow in the world
- Parameters
start (
list
offloat
) – The start[x, y, z]
location of the line. (see Coordinate System)end (
list
offloat
) – The end[x, y, z]
location of the arrowcolor (
list
) –[r, g, b]
color valuethickness (
float
) – thickness of the arrow
- draw_box(center, extent, color=None, thickness=10.0)
Draws a debug box in the world
- Parameters
center (
list
offloat
) – The start[x, y, z]
location of the box. (see Coordinate System)extent (
list
offloat
) – The[x, y, z]
extent of the boxcolor (
list
) –[r, g, b]
color valuethickness (
float
) – thickness of the lines
- draw_line(start, end, color=None, thickness=10.0)
Draws a debug line in the world
- Parameters
start (
list
offloat
) – The start[x, y, z]
location of the line. (see Coordinate System)end (
list
offloat
) – The end[x, y, z]
location of the linecolor (
list`
) –[r, g, b]
color valuethickness (
float
) – thickness of the line
- draw_point(loc, color=None, thickness=10.0)
Draws a debug point in the world
- Parameters
loc (
list
offloat
) – The[x, y, z]
start of the box. (see Coordinate System)color (
list
offloat
) –[r, g, b]
color valuethickness (
float
) – thickness of the point
- get_joint_constraints(agent_name, joint_name)
- Returns the corresponding swing1, swing2 and twist limit values for the
specified agent and joint. Will return None if the joint does not exist for the agent.
- Returns
obj )
- Return type
(
- info()
Returns a string with specific information about the environment. This information includes which agents are in the environment and which sensors they have.
- Returns
Information in a string format.
- Return type
str
- property modems
Gets all instances of OpticalModemSensor in the environment.
- Returns
List of all OpticalModemSensor in environment
- Return type
(
list
ofOpticalModemSensor
)
- property modems_id
Gets all ids of OpticalModemSensor in the environment.
- Returns
List of all OpticalModemSensor ids in environment
- Return type
(
list
ofint
)
- move_viewport(location, rotation)
Teleport the camera to the given location
By the next tick, the camera’s location and rotation will be updated
- Parameters
location (
list
offloat
) – The[x, y, z]
location to give the camera (see Coordinate System)rotation (
list
offloat
) – The[roll, pitch, yaw]
rotation to give the camera (see Rotations)
- publish(state)
Publishes current state to channels chosen by the scenario config.
- reset()
Resets the environment, and returns the state. If it is a single agent environment, it returns that state for that agent. Otherwise, it returns a dict from agent name to state.
- Returns (tuple or dict):
For single agent environment, returns the same as step.
For multi-agent environment, returns the same as tick.
- send_acoustic_message(id_from, id_to, msg_type, msg_data)
Send a message from one beacon to another.
- Parameters
id_from (
int
) – The integer ID of the transmitting modem.id_to (
int
) – The integer ID of the receiving modem.msg_type (
str
) – The message type. Seeholoocean.sensors.AcousticBeaconSensor
for a list.msg_data – The message to be transmitted. Currently can be any python object.
- send_optical_message(id_from, id_to, msg_data)
Sends data between various instances of OpticalModemSensor
- Parameters
id_from (
int
) – The integer ID of the transmitting modem.id_to (
int
) – The integer ID of the receiving modem.msg_data – The message to be transmitted. Currently can be any python object.
- send_world_command(name, num_params=None, string_params=None)
Send a world command.
A world command sends an abitrary command that may only exist in a specific world or package. It is given a name and any amount of string and number parameters that allow it to alter the state of the world.
If a command is sent that does not exist in the world, the environment will exit.
- Parameters
name (
str
) – The name of the command, ex “OpenDoor”(obj (string_params) – list of
int
): List of arbitrary number parameters(obj – list of
string
): List of arbitrary string parameters
- set_control_scheme(agent_name, control_scheme)
Set the control scheme for a specific agent.
- Parameters
agent_name (
str
) – The name of the agent to set the control scheme for.control_scheme (
int
) – A control scheme value (seeControlSchemes
)
- set_render_quality(render_quality)
Adjusts the rendering quality of HoloOcean.
- Parameters
render_quality (
int
) – An integer between 0 = Low Quality and 3 = Epic quality.
- should_render_viewport(render_viewport)
Controls whether the viewport is rendered or not
- Parameters
render_viewport (
boolean
) – If the viewport should be rendered
- spawn_prop(prop_type, location=None, rotation=None, scale=1, sim_physics=False, material='', tag='')
Spawns a basic prop object in the world like a box or sphere.
Prop will not persist after environment reset.
- Parameters
prop_type (
string
) – The type of prop to spawn. Can bebox
,sphere
,cylinder
, orcone
.location (
list
offloat
) – The[x, y, z]
location of the prop.rotation (
list
offloat
) – The[roll, pitch, yaw]
rotation of the prop.scale (
list
offloat
) or (float
) – The[x, y, z]
scalars to the prop size, where the default size is 1 meter. If given a single float value, then every dimension will be scaled to that value.sim_physics (
boolean
) – Whether the object is mobile and is affected by gravity.material (
string
) – The type of material (texture) to apply to the prop. Can bewhite
,gold
,cobblestone
,brick
,wood
,grass
,steel
, orblack
. If left empty, the prop will have the a simple checkered gray material.tag (
string
) – The tag to apply to the prop. Useful for task references.
- step(action, ticks=1, publish=True)
Supplies an action to the main agent and tells the environment to tick once. Primary mode of interaction for single agent environments.
- Parameters
action (
np.ndarray
) – An action for the main agent to carry out on the next tick.ticks (
int
) – Number of times to step the environment with this action. If ticks > 1, this function returns the last state generated.( (publish) – obj: bool): Whether or not to publish as defined by scenario. Defaults to True.
- Returns
- A 4tuple:
- State: Dictionary from sensor enum
(see
HoloOceanSensor
) tonp.ndarray
.
Reward (
float
): Reward returned by the environment.Terminal: The bool terminal signal returned by the environment.
Info: Any additional info, depending on the world. Defaults to None.
- Return type
(
dict
,float
,bool
, info)
- tick(num_ticks=1, publish=True)
Ticks the environment once. Normally used for multi-agent environments. :param num_ticks: Number of ticks to perform. Defaults to 1. :type num_ticks:
int
:param publish (: obj: bool): Whether or not to publish as defined by scenario. Defaults to True.- Returns
- A dictionary from agent name to its full state. The full state is another
dictionary from
holoocean.sensors.Sensors
enum to np.ndarray, containing the sensors information for each sensor. The sensors always include the reward and terminal sensors.Will return the state from the last tick executed.
- Return type
dict