Ignition Sensors

API Reference

5.0.0
ignition::sensors Namespace Reference

Sensors namespace. More...

Classes

class  AirPressureSensor
 AirPressure Sensor Class. More...
 
class  AltimeterSensor
 Altimeter Sensor Class. More...
 
class  CameraSensor
 Camera Sensor Class. More...
 
class  DepthCameraSensor
 Depth camera sensor class. More...
 
class  GaussianNoiseModel
 Gaussian noise class. More...
 
class  GpuLidarSensor
 GpuLidar Sensor Class. More...
 
class  ImageGaussianNoiseModel
 Gaussian noise class for image sensors. More...
 
class  ImageNoiseFactory
 
class  ImuSensor
 Imu Sensor Class. More...
 
class  Lidar
 Lidar Sensor Class. More...
 
class  LogicalCameraSensor
 Logical Camera Sensor Class. More...
 
class  MagnetometerSensor
 Magnetometer Sensor Class. More...
 
class  Manager
 Loads and runs sensors. More...
 
class  Noise
 Noise models for sensor output signals. More...
 
class  NoiseFactory
 Use this noise manager for creating and loading noise models. More...
 
class  RenderingEvents
 
class  RenderingSensor
 a rendering sensor class More...
 
class  RgbdCameraSensor
 RGBD camera sensor class. More...
 
class  Sensor
 a base sensor class More...
 
class  SensorFactory
 A factory class for creating sensors This class wll load a sensor plugin based on the given sensor type and instantiates a sensor object. More...
 
class  SensorPlugin
 Base sensor plugin interface. More...
 
class  SensorTypePlugin
 Templated class for instantiating sensors of the specified type. More...
 
class  ThermalCameraSensor
 Thermal camera sensor class. More...
 

Typedefs

typedef std::vector< CameraSensorPtrCameraSensor_V
 
typedef std::shared_ptr< CameraSensorCameraSensorPtr
 
typedef std::shared_ptr< GaussianNoiseModelGaussianNoiseModelPtr
 
typedef std::vector< GpuLidarSensorPtrGpuLidarSensor_V
 
typedef std::shared_ptr< GpuLidarSensorGpuLidarSensorPtr
 
typedef std::shared_ptr< ImageGaussianNoiseModelImageGaussianNoiseModelPtr
 Shared pointer to Noise. More...
 
typedef std::shared_ptr< NoiseNoisePtr
 
typedef std::vector< SensorPtrSensor_V
 
using SensorId = std::size_t
 A string used to identify a sensor. More...
 
typedef std::shared_ptr< SensorSensorPtr
 

Enumerations

enum  NoiseType : int { NONE = 0, CUSTOM = 1, GAUSSIAN = 2 }
 Which noise types we support. More...
 
enum  SensorCategory { IMAGE = 0, RAY = 1, OTHER = 2, CATEGORY_COUNT = 3 }
 SensorCategory is used to categorize sensors. This is used to put sensors into different threads. More...
 
enum  SensorNoiseType {
  SENSOR_NOISE_TYPE_BEGIN = 0, NO_NOISE = SENSOR_NOISE_TYPE_BEGIN, CAMERA_NOISE = 1, MAGNETOMETER_X_NOISE_TESLA = 2,
  MAGNETOMETER_Y_NOISE_TESLA = 3, MAGNETOMETER_Z_NOISE_TESLA = 4, ALTIMETER_VERTICAL_POSITION_NOISE_METERS = 5, ALTIMETER_VERTICAL_VELOCITY_NOISE_METERS_PER_S = 6,
  AIR_PRESSURE_NOISE_PASCALS = 7, ACCELEROMETER_X_NOISE_M_S_S = 8, ACCELEROMETER_Y_NOISE_M_S_S = 9, ACCELEROMETER_Z_NOISE_M_S_S = 10,
  GYROSCOPE_X_NOISE_RAD_S = 11, GYROSCOPE_Y_NOISE_RAD_S = 12, GYROSCOPE_Z_NOISE_RAD_S = 13, LIDAR_NOISE = 14,
  SENSOR_NOISE_TYPE_END
}
 

Variables

const SensorId NO_SENSOR = 0
 

Detailed Description

Sensors namespace.

Typedef Documentation

◆ CameraSensor_V

◆ CameraSensorPtr

◆ GaussianNoiseModelPtr

◆ GpuLidarSensor_V

◆ GpuLidarSensorPtr

◆ ImageGaussianNoiseModelPtr

◆ NoisePtr

◆ Sensor_V

◆ SensorId

A string used to identify a sensor.

◆ SensorPtr

Enumeration Type Documentation

◆ NoiseType

enum NoiseType : int
strong

Which noise types we support.

Enumerator
NONE 
CUSTOM 
GAUSSIAN 

◆ SensorCategory

SensorCategory is used to categorize sensors. This is used to put sensors into different threads.

Enumerator
IMAGE 

Image based sensor class. This type requires the rendering engine.

RAY 

Ray based sensor class.

OTHER 

A type of sensor is not a RAY or IMAGE sensor.

CATEGORY_COUNT 

Number of Sensor Categories.

◆ SensorNoiseType

Enumerator
SENSOR_NOISE_TYPE_BEGIN 
NO_NOISE 

Noise streams for the Camera sensor.

See also
CameraSensor
CAMERA_NOISE 

Noise streams for the Camera sensor.

See also
CameraSensor
MAGNETOMETER_X_NOISE_TESLA 

Magnetometer body-frame X axis noise in Tesla.

See also
MagnetometerSensor
MAGNETOMETER_Y_NOISE_TESLA 

Magnetometer body-frame Y axis noise in Tesla.

See also
MagnetometerSensor
MAGNETOMETER_Z_NOISE_TESLA 

Magnetometer body-frame Z axis noise in Tesla.

See also
MagnetometerSensor
ALTIMETER_VERTICAL_POSITION_NOISE_METERS 

Vertical noise stream for the altimeter sensor.

See also
AltimeterSensor
ALTIMETER_VERTICAL_VELOCITY_NOISE_METERS_PER_S 

Velocity noise streams for the altimeter sensor.

See also
AltimeterSensor
AIR_PRESSURE_NOISE_PASCALS 

Air Pressure noise streams for the air pressure sensor.

See also
AirPressureSensor
ACCELEROMETER_X_NOISE_M_S_S 

Accelerometer body-frame X axis noise in m/s^2.

See also
ImuSensor
ACCELEROMETER_Y_NOISE_M_S_S 

Accelerometer body-frame Y axis noise in m/s^2.

See also
ImuSensor
ACCELEROMETER_Z_NOISE_M_S_S 

Accelerometer body-frame Z axis noise in m/s^2.

See also
ImuSensor
GYROSCOPE_X_NOISE_RAD_S 

Gyroscope body-frame X axis noise in m/s^2.

See also
ImuSensor
GYROSCOPE_Y_NOISE_RAD_S 

Gyroscope body-frame X axis noise in m/s^2.

See also
ImuSensor
GYROSCOPE_Z_NOISE_RAD_S 

Gyroscope body-frame X axis noise in m/s^2.

See also
ImuSensor
LIDAR_NOISE 

Noise streams for the Lidar sensor.

See also
Lidar
SENSOR_NOISE_TYPE_END 

Variable Documentation

◆ NO_SENSOR

const SensorId NO_SENSOR = 0

Referenced by Manager::CreateSensor().