Commands
This module contains the classes used for formatting and sending commands to the HoloOcean backend. Most of these commands are just used internally by HoloOcean, regular users do not need to worry about these.
Classes:
|
Add a sensor to an agent |
|
Base class for Command objects. |
|
Manages pending commands to send to the client (the engine). |
Represents a list of commands |
|
|
Send a custom command to the currently loaded world. |
|
Draw debug geometry in the world. |
|
Set the number of ticks between captures of the RGB camera. |
|
Remove a sensor from an agent |
|
Adjust the rendering quality of HoloOcean |
|
Enable or disable the viewport. |
|
Rotate a sensor on the agent |
|
Set the number of ticks between captures of the RGB camera. |
|
Send information through OpticalModem. |
|
Spawn an agent in the world. |
|
Move the viewport camera (agent follower) |
- class holoocean.command.AddSensorCommand(sensor_definition)
Add a sensor to an agent
- Parameters:
sensor_definition (SensorDefinition) – Sensor to add
- class holoocean.command.Command
Base class for Command objects.
Commands are used for IPC between the holoocean python bindings and holoocean binaries.
Derived classes must set the
_command_type
.The order in which
add_number_parameters()
andadd_number_parameters()
are called is significant, they are added to an ordered list. Ensure that you are adding parameters in the order the client expects them.Methods:
add_number_parameters
(number)Add given number parameters to the internal list.
add_string_parameters
(string)Add given string parameters to the internal list.
set_command_type
(command_type)Set the type of the command.
to_json
()Converts to json.
- add_number_parameters(number)
Add given number parameters to the internal list.
- Parameters:
number (
list
ofint
/float
, or singularint
/float
) – A number or list of numbers to add to the parameters.
- add_string_parameters(string)
Add given string parameters to the internal list.
- Parameters:
string (
list
ofstr
orstr
) – A string or list of strings to add to the parameters.
- set_command_type(command_type)
Set the type of the command.
- Parameters:
command_type (
str
) – This is the name of the command that it will be set to.
- to_json()
Converts to json.
- Returns:
This object as a json string.
- Return type:
str
- class holoocean.command.CommandCenter(client)
Manages pending commands to send to the client (the engine).
- Parameters:
client (
HoloOceanClient
) – Client to send commands to
Methods:
clear
()Clears pending commands
enqueue_command
(command_to_send)Adds command to outgoing queue.
Writes the list of commands into the command buffer, if needed.
Attributes:
Returns: int: Size of commands queue
- clear()
Clears pending commands
- enqueue_command(command_to_send)
Adds command to outgoing queue.
- Parameters:
command_to_send (
Command
) – Command to add to queue
- handle_buffer()
Writes the list of commands into the command buffer, if needed.
Checks if we should write to the command buffer, writes all of the queued commands to the buffer, and then clears the contents of the self._commands list
- property queue_size
Returns: int: Size of commands queue
- class holoocean.command.CommandsGroup
Represents a list of commands
Can convert list of commands to json.
Methods:
add_command
(command)Adds a command to the list
clear
()Clear the list of commands.
to_json
()Attributes:
Returns: int: Size of commands group
- clear()
Clear the list of commands.
- property size
Returns: int: Size of commands group
- to_json()
- Returns:
Json for commands array object and all of the commands inside the array.
- Return type:
str
- class holoocean.command.CustomCommand(name, num_params=None, string_params=None)
Send a custom command to the currently loaded world.
- Parameters:
name (
str
) – The name of the command, ex “OpenDoor”(obj (string_params) – list of
int
): List of arbitrary number parameters(obj – list of
int
): List of arbitrary string parameters
- class holoocean.command.DebugDrawCommand(draw_type, start, end, color, thickness, lifetime)
Draw debug geometry in the world.
- Parameters:
draw_type (
int
) –The type of object to draw
0
: line1
: arrow2
: box3
: point
start (
list
offloat
) – The start[x, y, z]
location in meters of the object. (see Coordinate System)end (
list
offloat
) – The end[x, y, z]
location in meters of the object (not used for point, and extent for box)color (
list
offloat
) –[r, g, b]
color value (from 0 to 255).thickness (
float
) – thickness of the line/objectlifetime (
float
) – Number of simulation seconds the object should persist. If 0, makes persistent
- class holoocean.command.RGBCameraRateCommand(agent_name, sensor_name, ticks_per_capture)
Set the number of ticks between captures of the RGB camera.
- Parameters:
agent_name (
str
) – name of the agent to modifysensor_name (
str
) – name of the sensor to modifyticks_per_capture (
int
) – number of ticks between captures
- class holoocean.command.RemoveSensorCommand(agent, sensor)
Remove a sensor from an agent
- Parameters:
agent (
str
) – Name of agent to modifysensor (
str
) – Name of the sensor to remove
- class holoocean.command.RenderQualityCommand(render_quality)
Adjust the rendering quality of HoloOcean
- Parameters:
render_quality (int) – 0 = low, 1 = medium, 3 = high, 3 = epic
- class holoocean.command.RenderViewportCommand(render_viewport)
Enable or disable the viewport. Note that this does not prevent the viewport from being shown, it just prevents it from being updated.
- Parameters:
render_viewport (
bool
) – If viewport should be rendered
- class holoocean.command.RotateSensorCommand(agent, sensor, rotation)
Rotate a sensor on the agent
- Parameters:
agent (
str
) – Name of agentsensor (
str
) – Name of the sensor to rotaterotation (
list
offloat
) –[roll, pitch, yaw]
rotation for sensor.
- class holoocean.command.SendAcousticMessageCommand(from_agent_name, from_sensor_name, to_agent_name, to_sensor_name)
Set the number of ticks between captures of the RGB camera.
- Parameters:
agent_name (
str
) – name of the agent to modifysensor_name (
str
) – name of the sensor to modifynum (
int
) – number of ticks between captures
- class holoocean.command.SendOpticalMessageCommand(from_agent_name, from_sensor_name, to_agent_name, to_sensor_name)
Send information through OpticalModem.
- class holoocean.command.SpawnAgentCommand(location, rotation, name, agent_type, is_main_agent=False)
Spawn an agent in the world.
- Parameters:
location (
list
offloat
) –[x, y, z]
location to spawn agent (see Coordinate System)name (
str
) – The name of the agent.agent_type (
str
or type) – The type of agent to spawn (UAVAgent, NavAgent, …)
Methods:
set_location
(location)Set where agent will be spawned.
set_name
(name)Set agents name
set_rotation
(rotation)Set where agent will be spawned.
set_type
(agent_type)Set the type of agent.
- set_location(location)
Set where agent will be spawned.
- Parameters:
location (
list
offloat
) –[x, y, z]
location to spawn agent (see Coordinate System)
- set_name(name)
Set agents name
- Parameters:
name (
str
) – The name to set the agent to.
- set_rotation(rotation)
Set where agent will be spawned.
- Parameters:
rotation (
list
offloat
) –[roll, pitch, yaw]
rotation for agent. (see Rotations)
- set_type(agent_type)
Set the type of agent.
- Parameters:
agent_type (
str
ortype
) – The type of agent to spawn.
- class holoocean.command.TeleportCameraCommand(location, rotation)
Move the viewport camera (agent follower)
- 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)