Sensors
Definition of all of the sensor information. The UE settings for sensors are such that the motion ticks happen before the sensor ticks.
Classes:
|
Acoustic Beacon Sensor. |
|
Doppler Velocity Log Sensor. |
|
Pressure/Depth Sensor. |
|
Gives all relevant information needed for implementing custom dynamics. |
|
Gets the location of the agent in the world if the agent is close enough to the surface. |
|
Base class for a sensor |
|
Inertial Measurement Unit sensor. |
|
Simulates an imaging sonar. |
|
Gets the location of the agent in the world. |
|
Gets the global x-axis (or given vector) in the local frame. |
|
Handles communication between agents using an optical modem. |
|
Gets the forward, right, and up vector for the agent. |
|
Gets the forward, right, and up vector for the agent. |
|
Simulates a multibeam profiling sonar. |
|
Captures agent's view. |
|
Returns distances to nearest collisions in the directions specified by the parameters. |
|
Gets the rotation of the agent in the world, with rotation XYZ about the fixed frame, in degrees. |
|
A class for new sensors and their parameters, to be used for adding new sensors. |
Given a sensor definition, constructs the appropriate HoloOceanSensor object. |
|
|
Simulates a sidescan sonar. |
|
Simulates an echosounder, which is a sonar sensor with a single cone shaped beam. |
|
Returns the x, y, and z velocity of the sensor in the global frame. |
|
Captures what the viewport is seeing. |
|
Returns any numeric value from the world corresponding to a given key. |
- class holoocean.sensors.AcousticBeaconSensor(client, agent_name, agent_type, name='AcousticBeaconSensor', config=None)
Acoustic Beacon Sensor. Can send message to other beacon from the
send_acoustic_message()
command.Returning array depends on sent message type. Note received message will be delayed due to time of acoustic wave traveling. Possibly message types are, with ϕ representing the azimuth, ϴ elevation, r range, and d depth in water,
OWAY
: One way message that sends["OWAY", from_sensor, payload]
OWAYU
: One way message that sends["OWAYU", from_sensor, payload, ϕ, ϴ]
MSG_REQ
: Requests a return message of MSG_RESP and sends["MSG_REQ", from_sensor, payload]
MSG_RESP
: Return message that sends["MSG_RESP", from_sensor, payload]
MSG_REQU
: Requests a return message of MSG_RESPU and sends["MSG_REQU", from_sensor, payload, ϕ, ϴ]
MSG_RESPU
: Return message that sends["MSG_RESPU", from_sensor, payload, ϕ, ϴ, r]
MSG_REQX
: Requests a return message of MSG_RESPX and sends["MSG_REQX", from_sensor, payload, ϕ, ϴ, d]
MSG_RESPX
: Return message that sends["MSG_RESPX", from_sensor, payload, ϕ, ϴ, r, d]
These messages types are based on the Blueprint Subsea SeaTrac X150
Configuration
The
configuration
block (see Configuration Block) accepts the following options:id
: Id of this sensor. If not given, they are numbered sequentially.CheckVisible
: Whether to check for linear line of sight to vehicle when verify message will be received. Used when sending data. Defaults to false.MaxDistance
: Max Distance in meters of AcousticBeacon. Used when sending data. Defaults to no max distance.DistanceSigma
/DistanceCov
: Determines the standard deviation/covariance of the noise on MaxDistance. Must be scalar value. (default 0 => no noise)
Attributes:
The shape of the sensor data
The type of data in the sensor
Get the sensor data buffer
- property data_shape
The shape of the sensor data
- Returns:
Sensor data shape
- Return type:
tuple
- property dtype
The type of data in the sensor
- Returns:
Type of sensor data
- Return type:
numpy dtype
- property sensor_data
Get the sensor data buffer
- Returns:
Current sensor data
- Return type:
np.ndarray
of sizeself.data_shape
- class holoocean.sensors.DVLSensor(client, agent_name, agent_type, name='DVLSensor', config=None)
Doppler Velocity Log Sensor.
Returns a 1D numpy array of:
[velocity_x, velocity_y, velocity_z, range_x_forw, range_y_forw, range_x_back, range_y_back]
With the range potentially not returning if
ReturnRange
is set to false.Configuration
The
configuration
block (see Configuration Block) accepts the following options:Elevation
: Angle of each acoustic beam off z-axis pointing down. Only used for noise/visualization. Defaults to 22.5 degrees => 45 field of view.DebugLines
: Whether to show lines of each beam. Defaults to false.VelSigma
/VelCov
: Covariance/Std to be applied to each beam velocity. Can be scalar, 4-vector or 4x4-matrix. Set one or the other. Defaults to 0 => no noise.ReturnRange
: Boolean of whether range of beams should also be returned. Defaults to true.MaxRange
: Maximum range that can be returned by the beams.RangeSigma
/RangeCov
: Covariance/Std to be applied to each beam range. Can be scalar, 4-vector or 4x4-matrix. Set one or the other. Defaults to 0 => no noise.
Attributes:
The shape of the sensor data
The type of data in the sensor
- property data_shape
The shape of the sensor data
- Returns:
Sensor data shape
- Return type:
tuple
- property dtype
The type of data in the sensor
- Returns:
Type of sensor data
- Return type:
numpy dtype
- class holoocean.sensors.DepthSensor(client, agent_name, agent_type, name='DepthSensor', config=None)
Pressure/Depth Sensor.
Returns a 1D numpy array of:
[position_z]
Configuration
The
configuration
block (see Configuration Block) accepts the following options:Sigma
/Cov
: Covariance/Std to be applied, a scalar. Defaults to 0 => no noise.
Attributes:
The shape of the sensor data
The type of data in the sensor
- property data_shape
The shape of the sensor data
- Returns:
Sensor data shape
- Return type:
tuple
- property dtype
The type of data in the sensor
- Returns:
Type of sensor data
- Return type:
numpy dtype
- class holoocean.sensors.DynamicsSensor(client, agent_name, agent_type, name='DynamicsSensor', config=None)
Gives all relevant information needed for implementing custom dynamics. Returns are all in the global frame and are as follows:
[acceleration, velocity, position, angular accel., angular velocity, rpy]
all of which are 3-vectors and rpy is roll, pitch, and yaw. This is the ONLY sensor that by default doesn’t operate in its socket, but rather in the COM. This is mostly for convenience since 99% of the time when doing custom dynamics the information is wanted at the COM.
Configuration
The
configuration
block (see Configuration Block) accepts the following options:UseCOM
: Whether to return data relative to the COM or the specified socket. Defaults to true.UseRPY
: Whether to return orientation as roll, pitch, yaw, or as a quaternion. Defaults to true. When true, sensor returns an 18 vector, when false sensor returns as 19 vector. Quaternion is specified with scalar as last value ie x,y,z,w.
Attributes:
The shape of the sensor data
The type of data in the sensor
- property data_shape
The shape of the sensor data
- Returns:
Sensor data shape
- Return type:
tuple
- property dtype
The type of data in the sensor
- Returns:
Type of sensor data
- Return type:
numpy dtype
- class holoocean.sensors.GPSSensor(client, agent_name, agent_type, name='GPSSensor', config=None)
Gets the location of the agent in the world if the agent is close enough to the surface.
Returns coordinates in
[x, y, z]
format (see Coordinate System)Configuration
The
configuration
block (see Configuration Block) accepts the following options:Sigma
/Cov
: Covariance/Std of measurement. Can be scalar, 3-vector or 3x3-matrix. Set one or the other. Defaults to 0 => no noise.Depth
: How deep in the water we can still receive GPS messages in meters. Defaults to 2m.DepthSigma
/DepthCov
: Covariance/Std of depth. Must be a scalar. Set one or the other. Defaults to 0 => no noise.
Attributes:
The shape of the sensor data
The type of data in the sensor
Get the sensor data buffer
- property data_shape
The shape of the sensor data
- Returns:
Sensor data shape
- Return type:
tuple
- property dtype
The type of data in the sensor
- Returns:
Type of sensor data
- Return type:
numpy dtype
- property sensor_data
Get the sensor data buffer
- Returns:
Current sensor data
- Return type:
np.ndarray
of sizeself.data_shape
- class holoocean.sensors.HoloOceanSensor(client, agent_name=None, agent_type=None, name='DefaultSensor', config=None)
Base class for a sensor
- Parameters:
client (
HoloOceanClient
) – Client attached to a sensoragent_name (
str
) – Name of the parent agentagent_type (
str
) – Type of the parent agentname (
str
) – Name of the sensorconfig (
dict
) – Configuration dictionary to pass to the engine
Attributes:
The shape of the sensor data
The type of data in the sensor
Get the sensor data buffer
Methods:
rotate
(rotation)Rotate the sensor.
- property data_shape
The shape of the sensor data
- Returns:
Sensor data shape
- Return type:
tuple
- property dtype
The type of data in the sensor
- Returns:
Type of sensor data
- Return type:
numpy dtype
- rotate(rotation)
Rotate the sensor. It will be applied in approximately three ticks.
step()
ortick()
.)This will not persist after a call to reset(). If you want a persistent rotation for a sensor, specify it in your scenario configuration.
- Parameters:
rotation (
list
offloat
) – rotation for sensor (see Rotations).
- property sensor_data
Get the sensor data buffer
- Returns:
Current sensor data
- Return type:
np.ndarray
of sizeself.data_shape
- class holoocean.sensors.IMUSensor(client, agent_name, agent_type, name='IMUSensor', config=None)
Inertial Measurement Unit sensor.
Returns a 2D numpy array of:
[ [accel_x, accel_y, accel_z], [ang_vel_roll, ang_vel_pitch, ang_vel_yaw], [accel_bias_x, accel_bias_y, accel_bias_z], [ang_vel_bias_roll, ang_vel_bias_pitch, ang_vel_bias_yaw] ]
where the accleration components are in m/s and the angular velocity is in rad/s.
Configuration
The
configuration
block (see Configuration Block) accepts the following options:AccelSigma
/AccelCov
: Covariance/Std for acceleration component. Can be scalar, 3-vector or 3x3-matrix. Set one or the other. Defaults to 0 => no noise.AngVelSigma
/AngVelCov
: Covariance/Std for angular velocity component. Can be scalar, 3-vector or 3x3-matrix. Set one or the other. Defaults to 0 => no noise.AccelBiasSigma
/AccelCBiasov
: Covariance/Std for acceleration bias component. Can be scalar, 3-vector or 3x3-matrix. Set one or the other. Defaults to 0 => no noise.AngVelBiasSigma
/AngVelBiasCov
: Covariance/Std for acceleration bias component. Can be scalar, 3-vector or 3x3-matrix. Set one or the other. Defaults to 0 => no noise.ReturnBias
: Whether the sensor should return the bias along with accel/ang. vel. Defaults to false.
Attributes:
The shape of the sensor data
The type of data in the sensor
- property data_shape
The shape of the sensor data
- Returns:
Sensor data shape
- Return type:
tuple
- property dtype
The type of data in the sensor
- Returns:
Type of sensor data
- Return type:
numpy dtype
- class holoocean.sensors.ImagingSonar(client, agent_name, agent_type, name='ImagingSonar', config=None)
Simulates an imaging sonar. See Configuring Octree for more on how to configure the octree that is used.
The
configuration
block (see Configuration Block) accepts any of the options in the following sections.Basic Configuration
Azimuth
: Azimuth (side to side) angle visible in degrees, defaults to 120.Elevation
: Elevation angle (up and down) visible in degrees, defaults to 20.RangeMin
: Minimum range visible in meters, defaults to 0.1.RangeMax
: Maximum range visible in meters, defaults to 10.RangeBins
/RangeRes
: Number of range bins of resulting image, or resolution (length in meters) of each bin. Set one or the other. Defaults to 512 bins.AzimuthBins
/AzimuthRes
: Number of azimuth bins of resulting image, or resolution (length in degrees) of each bin. Set one or the other. Defaults to 512 bins.
Noise Configuration
AddSigma
/AddCov
: Additive noise std/covariance from a Rayleigh distribution. Needs to be a float. Set one or the other. Defaults to 0, or off.MultSigma
/MultCov
: Multiplication noise std/covariance from a normal distribution. Needs to be a float. Set one or the other. Defaults to 0, or off.MultiPath
: Whether to compute multipath or not. Defaults to False.ClusterSize
: Size of cluster when multipath is enabled. Defaults to 5.ScaleNoise
: Whether to scale the returned intensities or not. Defaults to False.AzimuthStreaks
: What sort of azimuth artifacts to introduce. -1 is a removal artifact, 0 is no artifact, and 1 is increased gain artifact. Defaults to 0.RangeSigma
: Additive noise std from an exponential distribution that will be added to the range measurements, and the intensities will be scaled by the pdf. Needs to be a float. Defaults to 0, or off.
Advanced Configuration
ShowWarning
: Whether to show on screen warning about sonar computation happening. Defaults to True.ElevationBins
/ElevationRes
: Number of elevation bins used when shadowing is done, or resolution (length in degrees) of each bin. Set one or the other. By default this is computed based on the octree size and the min/max range. Should only be set if shadowing isn’t working.InitOctreeRange
: Upon startup, all mid-level octrees within this distance of the agent will be created.ViewRegion
: Turns on green lines to see visible region. Defaults to False.ViewOctree
: What octree leaves to show. Less than -1 means none, -1 means all, and anything greater than or equal to 0 shows the corresponding beam index. Defaults to -10.ShadowEpsilon
: What constitutes a break between clusters when shadowing. Defaults to 4*OctreeMin.WaterDensity
: Density of water in kg/m^3. Defaults to 997.WaterSpeedSound
: Speed of sound in water in m/s. Defaults to 1480.UseApprox
: Whether to use the faster approximation of Atan2 or the slower exact implementation. Defaults to True.
Attributes:
The shape of the sensor data
The type of data in the sensor
- property data_shape
The shape of the sensor data
- Returns:
Sensor data shape
- Return type:
tuple
- property dtype
The type of data in the sensor
- Returns:
Type of sensor data
- Return type:
numpy dtype
- class holoocean.sensors.LocationSensor(client, agent_name, agent_type, name='LocationSensor', config=None)
Gets the location of the agent in the world.
Returns coordinates in
[x, y, z]
format (see Coordinate System)Configuration
The
configuration
block (see Configuration Block) accepts the following options:Sigma
/Cov
: Covariance/Std. Can be scalar, 3-vector or 3x3-matrix. Set one or the other. Defaults to 0 => no noise.
Attributes:
The shape of the sensor data
The type of data in the sensor
- property data_shape
The shape of the sensor data
- Returns:
Sensor data shape
- Return type:
tuple
- property dtype
The type of data in the sensor
- Returns:
Type of sensor data
- Return type:
numpy dtype
- class holoocean.sensors.MagnetometerSensor(client, agent_name, agent_type, name='MagnetometerSensor', config=None)
Gets the global x-axis (or given vector) in the local frame.
Configuration
The
configuration
block (see Configuration Block) accepts the following options:Sigma
/Cov
: Covariance/Std of measurement. Can be scalar, 3-vector or 3x3-matrix. Set one or the other. Defaults to 0 => no noise.MagneticVector
: The given 3-vector to measure in the global frame. Defaults to [1,0,0].
Attributes:
The shape of the sensor data
The type of data in the sensor
- property data_shape
The shape of the sensor data
- Returns:
Sensor data shape
- Return type:
tuple
- property dtype
The type of data in the sensor
- Returns:
Type of sensor data
- Return type:
numpy dtype
- class holoocean.sensors.OpticalModemSensor(client, agent_name, agent_type, name='OpticalModemSensor', config=None)
Handles communication between agents using an optical modem. Can send message to other modem from the
send_optical_message()
command.Configuration
The
configuration
block (see Configuration Block) accepts the following options:id
: Id of this sensor. If not given, they are numbered sequentially.MaxDistance
: Max Distance in meters of OpticalModem. Used when sending data. (default 50)DistanceSigma
/DistanceCov
: Determines the standard deviation/covariance of the noise on MaxDistance. Must be scalar value. (default 0 => no noise)LaserAngle
: Angle of lasers from origin. Measured in degrees. Used when sending data. (default 60)AngleSigma
/AngleCov
: Determines the standard deviation of the noise on LaserAngle. Must be scalar value. (default 0 => no noise)LaserDebug
: Show debug traces. (default false)DebugNumSides
: Number of sides on the debug cone. (default 72)
Attributes:
The shape of the sensor data
The type of data in the sensor
Get the sensor data buffer
- property data_shape
The shape of the sensor data
- Returns:
Sensor data shape
- Return type:
tuple
- property dtype
The type of data in the sensor
- Returns:
Type of sensor data
- Return type:
numpy dtype
- property sensor_data
Get the sensor data buffer
- Returns:
Current sensor data
- Return type:
np.ndarray
of sizeself.data_shape
- class holoocean.sensors.OrientationSensor(client, agent_name=None, agent_type=None, name='DefaultSensor', config=None)
Gets the forward, right, and up vector for the agent. Note that this is based on the sensor’s frame, not the agent’s frame so in the IMU socket, it will be NED, and in COM socket it will NWU. Our provided configurations have the sensor in the IMU socket.
Returns a 2D numpy array of
[ [forward_x, right_x, up_x], [forward_y, right_y, up_y], [forward_z, right_z, up_z] ]
Attributes:
The shape of the sensor data
The type of data in the sensor
- property data_shape
The shape of the sensor data
- Returns:
Sensor data shape
- Return type:
tuple
- property dtype
The type of data in the sensor
- Returns:
Type of sensor data
- Return type:
numpy dtype
- class holoocean.sensors.PoseSensor(client, agent_name=None, agent_type=None, name='DefaultSensor', config=None)
Gets the forward, right, and up vector for the agent. Note that this is based on the sensor’s frame, not the agent’s frame so in the IMU socket, it will be NED, and in COM socket it will NWU. Our provided configurations have the sensor in the IMU socket.
Returns a 2D numpy array of
[ [R, p], [0, 1] ]
where R is the rotation matrix (See OrientationSensor) and p is the robot world location (see LocationSensor)
Attributes:
The shape of the sensor data
The type of data in the sensor
- property data_shape
The shape of the sensor data
- Returns:
Sensor data shape
- Return type:
tuple
- property dtype
The type of data in the sensor
- Returns:
Type of sensor data
- Return type:
numpy dtype
- class holoocean.sensors.ProfilingSonar(client, agent_name, agent_type, name='ProfilingSonar', config=None)
Simulates a multibeam profiling sonar. This is largely based off of the imaging sonar (
ImagingSonar
), just with different defaults. See Configuring Octree for more on how to configure the octree that is used.The
configuration
block (see Configuration Block) accepts any of the options in the following sections.Basic Configuration
Azimuth
: Azimuth (side to side) angle visible in degrees, defaults to 120.Elevation
: Elevation angle (up and down) visible in degrees, defaults to 1.RangeMin
: Minimum range visible in meters, defaults to 0.5.RangeMax
: Maximum range visible in meters, defaults to 75.RangeBins
/RangeRes
: Number of range bins of resulting image, or resolution (length in meters) of each bin. Set one or the other. Defaults to 750 bins.AzimuthBins
/AzimuthRes
: Number of azimuth bins of resulting image, or resolution (length in degrees) of each bin. Set one or the other. Defaults to 480 bins.
Noise Configuration
AddSigma
/AddCov
: Additive noise std/covariance from a Rayleigh distribution. Needs to be a float. Set one or the other. Defaults to 0, or off.MultSigma
/MultCov
: Multiplication noise std/covariance from a normal distribution. Needs to be a float. Set one or the other. Defaults to 0, or off.MultiPath
: Whether to compute multipath or not. Defaults to False.ClusterSize
: Size of cluster when multipath is enabled. Defaults to 5.ScaleNoise
: Whether to scale the returned intensities or not. Defaults to False.AzimuthStreaks
: What sort of azimuth artifacts to introduce. -1 is a removal artifact, 0 is no artifact, and 1 is increased gain artifact. Defaults to 0.
Advanced Configuration
ShowWarning
: Whether to show on screen warning about sonar computation happening. Defaults to True.ElevationBins
/ElevationRes
: Number of elevation bins used when shadowing is done, or resolution (length in degrees) of each bin. Set one or the other. By default this is computed based on the octree size and the min/max range. Should only be set if shadowing isn’t working.InitOctreeRange
: Upon startup, all mid-level octrees within this distance of the agent will be created.ViewRegion
: Turns on green lines to see visible region. Defaults to False.ViewOctree
: What octree leaves to show. Less than -1 means none, -1 means all, and anything greater than or equal to 0 shows the corresponding beam index. Defaults to -10.ShadowEpsilon
: What constitutes a break between clusters when shadowing. Defaults to 4*OctreeMin.WaterDensity
: Density of water in kg/m^3. Defaults to 997.WaterSpeedSound
: Speed of sound in water in m/s. Defaults to 1480.UseApprox
: Whether to use the faster approximation of Atan2 or the slower exact implementation. Defaults to True.
- class holoocean.sensors.RGBCamera(client, agent_name, agent_type, name='RGBCamera', config=None)
Captures agent’s view.
The default capture resolution is 256x256x256x4, corresponding to the RGBA channels. The resolution can be increased, but will significantly impact performance.
Configuration
The
configuration
block (see Configuration Block) accepts the following options:CaptureWidth
: Width of captured imageCaptureHeight
: Height of captured image
Attributes:
The shape of the sensor data
The type of data in the sensor
Methods:
set_ticks_per_capture
(ticks_per_capture)Sets this RGBCamera to capture a new frame every ticks_per_capture.
- property data_shape
The shape of the sensor data
- Returns:
Sensor data shape
- Return type:
tuple
- property dtype
The type of data in the sensor
- Returns:
Type of sensor data
- Return type:
numpy dtype
- set_ticks_per_capture(ticks_per_capture)
Sets this RGBCamera to capture a new frame every ticks_per_capture.
The sensor’s image will remain unchanged between captures.
This method must be called after every call to env.reset.
- Parameters:
ticks_per_capture (
int
) – The amount of ticks to wait between camera captures.
- class holoocean.sensors.RangeFinderSensor(client, agent_name, agent_type, name='RangeFinderSensor', config=None)
Returns distances to nearest collisions in the directions specified by the parameters. For example, if an agent had two range sensors at different angles with 24 lasers each, the LaserDebug traces would look something like this:
That is, for 1 laser, you’d have 1 laser facing forward, for 3, you’d have one forward, with the other 2 distributed evenly along the circle, at 120 degree intervals, and for 24, you’d have a laser spaced every 15 degrees.
Configuration
The
configuration
block (see Configuration Block) accepts the following options:LaserMaxDistance
: Max Distance in meters of RangeFinder. (default 10)LaserCount
: Number of lasers in sensor. Lasers are distributed evenly along the cone defined by laser angle. (default 1)LaserAngle
: Angle of elevation of lasers from origin. Measured in degrees. Straight up would be 90 degrees, down would be -90. (default 0)LaserDebug
: Show debug traces. (default false)
Attributes:
The shape of the sensor data
The type of data in the sensor
- property data_shape
The shape of the sensor data
- Returns:
Sensor data shape
- Return type:
tuple
- property dtype
The type of data in the sensor
- Returns:
Type of sensor data
- Return type:
numpy dtype
- class holoocean.sensors.RotationSensor(client, agent_name=None, agent_type=None, name='DefaultSensor', config=None)
Gets the rotation of the agent in the world, with rotation XYZ about the fixed frame, in degrees.
Returns
[roll, pitch, yaw]
(see Rotations)Attributes:
The shape of the sensor data
The type of data in the sensor
- property data_shape
The shape of the sensor data
- Returns:
Sensor data shape
- Return type:
tuple
- property dtype
The type of data in the sensor
- Returns:
Type of sensor data
- Return type:
numpy dtype
- class holoocean.sensors.SensorDefinition(agent_name, agent_type, sensor_name, sensor_type, socket='', location=(0, 0, 0), rotation=(0, 0, 0), config=None, existing=False, lcm_channel=None, tick_every=None)
A class for new sensors and their parameters, to be used for adding new sensors.
- Parameters:
agent_name (
str
) – The name of the parent agent.agent_type (
str
) – The type of the parent agentsensor_name (
str
) – The name of the sensor.sensor_type (
str
orHoloOceanSensor
) – The type of the sensor.socket (
str
, optional) – The name of the socket to attach sensor to.location (Tuple of
float
, optional) –[x, y, z]
coordinates to place sensor relative to agent (or socket) (see Coordinate System).rotation (Tuple of
float
, optional) –[roll, pitch, yaw]
to rotate sensor relative to agent (see Rotations)config (
dict
) – Configuration dictionary for the sensor, to pass to engine
Methods:
Gets the configuration dictionary as a string ready for transport
- get_config_json_string()
Gets the configuration dictionary as a string ready for transport
- Returns:
The configuration as an escaped json string
- Return type:
(
str
)
- class holoocean.sensors.SensorFactory
Given a sensor definition, constructs the appropriate HoloOceanSensor object.
Methods:
build_sensor
(client, sensor_def)Constructs a given sensor associated with client
- static build_sensor(client, sensor_def)
Constructs a given sensor associated with client
- Parameters:
client (
str
) – Name of the agent this sensor is attached tosensor_def (
SensorDefinition
) – Sensor definition to construct
Returns:
- class holoocean.sensors.SidescanSonar(client, agent_name, agent_type, name='SidescanSonar', config=None)
Simulates a sidescan sonar. See Configuring Octree for more on how to configure the octree that is used.
The
configuration
block (see Configuration Block) accepts any of the options in the following sections.Basic Configuration
Azimuth
: Azimuth (side to side) angle visible in degrees, defaults to 170.Elevation
: Elevation angle (up and down) visible in degrees, defaults to 0.25.RangeMin
: Minimum range visible in meters, defaults to 0.5.RangeMax
: Maximum range visible in meters, defaults to 35.RangeBins
/RangeRes
: Number of range bins of resulting image, or resolution (length in meters) of each bin. Set one or the other. Defaults to 0.05 m.
Noise Configuration
AddSigma
/AddCov
: Additive noise std/covariance from a Rayleigh distribution. Needs to be a float. Set one or the other. Defaults to 0, or off.MultSigma
/MultCov
: Multiplication noise std/covariance from a normal distribution. Needs to be a float. Set one or the other. Defaults to 0, or off.
Advanced Configuration
ShowWarning
: Whether to show on screen warning about sonar computation happening. Defaults to True.AzimuthBins
/AzimuthRes
: Number of azimuth bins of resulting image, or resolution (length in degrees) of each bin. Set one or the other. By default this is computed based on the OctreeMin.ElevationBins
/ElevationRes
: Number of elevation bins used when shadowing is done, or resolution (length in degrees) of each bin. Set one or the other. By default this is computed based on the octree size and the min range. Should only be set if shadowing isn’t working.InitOctreeRange
: Upon startup, all mid-level octrees within this distance of the agent will be created.ViewRegion
: Turns on green lines to see visible region. Defaults to False.ViewOctree
: What octree leaves to show. Less than -1 means none, -1 means all, and anything greater than or equal to 0 shows the corresponding beam index. Defaults to -10.ShadowEpsilon
: What constitutes a break between clusters when shadowing. Defaults to 4*OctreeMin.WaterDensity
: Density of water in kg/m^3. Defaults to 997.WaterSpeedSound
: Speed of sound in water in m/s. Defaults to 1480.UseApprox
: Whether to use the faster approximation of Atan2 or the slower exact implementation. Defaults to True.
Attributes:
The shape of the sensor data
The type of data in the sensor
- property data_shape
The shape of the sensor data
- Returns:
Sensor data shape
- Return type:
tuple
- property dtype
The type of data in the sensor
- Returns:
Type of sensor data
- Return type:
numpy dtype
- class holoocean.sensors.SinglebeamSonar(client, agent_name, agent_type, name='SinglebeamSonar', config=None)
Simulates an echosounder, which is a sonar sensor with a single cone shaped beam. See Configuring Octree for more on how to configure the octree that is used.
Returns a 1D numpy array of the average intensities held in each range bin of the sensor. The length of the array is specified by the number of range bins chosen for the sensor.
Configuration
The
configuration
block (see Configuration Block) accepts the following options:The
configuration
block (see Configuration Block) accepts any of the options in the following sections.Basic Configuration
OpeningAngle
: Opening angle of the cone visible in degrees, defaults to 30. In this documentation, the opening angle would be 2 times the semi-vertical angle of the cone.RangeMin
: Minimum range visible in meters, defaults to 0.5.RangeMax
: Maximum range visible in meters, defaults to 10.RangeBins
/RangeRes
: Number of range bins of resulting image, or resolution (length in meters) of each bin. Set one or the other. Defaults to 200 bins.
Noise Configuration
AddSigma
/AddCov
: Additive noise std/covariance from a Rayleigh distribution. Needs to be a float. Set one or the other. Defaults to 0, or off.MultSigma
/MultCov
: Multiplication noise std/covariance from a normal distribution. Needs to be a float. Set one or the other. Defaults to 0, or off.RangeSigma
: Additive noise std from an exponential distribution that will be added to the range measurements. Needs to be a float. Defaults to 0/off.
Advanced Configuration
ShowWarning
: Whether to show on screen warning about sonar computation happening. Defaults to True.OpeningAngleBins
/OpeningAngleRes
: Number of OpeningAngle bins used when shadowing is done, or resolution (length in degrees) of each bin. Set one or the other. By default this is computed based on the octree size and the min/max range. Should only be set if shadowing isn’t working.CentralAngleBins
/CentralAngleRes
: Number of CentralAngle bins used when shadowing is done, or resolution (length in degrees) of each bin. Set one or the other. By default this is computed based on the octree size and the min/max range. Should only be set if shadowing isn’t working.InitOctreeRange
: Upon startup, all mid-level octrees within this distance of the agent will be created.ViewRegion
: Turns on green lines to see visible region. Defaults to False.ViewOctree
: What octree leaves to show. Less than -1 means none, -1 means all, and anything greater than or equal to 0 shows the corresponding beam index. Defaults to -10.ShadowEpsilon
: What constitutes a break between clusters when shadowing. Defaults to 4*OctreeMin.WaterDensity
: Density of water in kg/m^3. Defaults to 997.WaterSpeedSound
: Speed of sound in water in m/s. Defaults to 1480.UseApprox
: Whether to use the faster approximation of Atan2 or the slower exact implementation. Defaults to True.
Attributes:
The shape of the sensor data
The type of data in the sensor
- property data_shape
The shape of the sensor data
- Returns:
Sensor data shape
- Return type:
tuple
- property dtype
The type of data in the sensor
- Returns:
Type of sensor data
- Return type:
numpy dtype
- class holoocean.sensors.VelocitySensor(client, agent_name=None, agent_type=None, name='DefaultSensor', config=None)
Returns the x, y, and z velocity of the sensor in the global frame.
Attributes:
The shape of the sensor data
The type of data in the sensor
- property data_shape
The shape of the sensor data
- Returns:
Sensor data shape
- Return type:
tuple
- property dtype
The type of data in the sensor
- Returns:
Type of sensor data
- Return type:
numpy dtype
- class holoocean.sensors.ViewportCapture(client, agent_name, agent_type, name='ViewportCapture', config=None)
Captures what the viewport is seeing.
The ViewportCapture is faster than the RGB camera, but there can only be one camera and it must capture what the viewport is capturing. If performance is critical, consider this camera instead of the RGBCamera.
It may be useful to position the camera with
teleport_camera()
.Configuration
The
configuration
block (see Configuration Block) accepts the following options:CaptureWidth
: Width of captured imageCaptureHeight
: Height of captured image
THESE DIMENSIONS MUST MATCH THE VIEWPORT DIMENSTIONS
If you have configured the size of the viewport (
window_height/width
), you must make sure thatCaptureWidth/Height
of this configuration block is set to the same dimensions.The default resolution is
1280x720
, matching the default Viewport resolution.Attributes:
The shape of the sensor data
The type of data in the sensor
- property data_shape
The shape of the sensor data
- Returns:
Sensor data shape
- Return type:
tuple
- property dtype
The type of data in the sensor
- Returns:
Type of sensor data
- Return type:
numpy dtype
- class holoocean.sensors.WorldNumSensor(client, agent_name=None, agent_type=None, name='DefaultSensor', config=None)
Returns any numeric value from the world corresponding to a given key. This is world specific.
Attributes:
The shape of the sensor data
The type of data in the sensor
- property data_shape
The shape of the sensor data
- Returns:
Sensor data shape
- Return type:
tuple
- property dtype
The type of data in the sensor
- Returns:
Type of sensor data
- Return type:
numpy dtype