Sensors namespace. More...
Classes | |
| class | AltimeterSensor |
| AltimeterSensor to provide vertical position and velocity. More... | |
| class | CameraSensor |
| Basic camera sensor. More... | |
| class | ContactSensor |
| Contact sensor. More... | |
| class | DepthCameraSensor |
| class | ForceTorqueSensor |
| Sensor for measure force and torque on a joint. More... | |
| class | GaussianNoiseModel |
| Gaussian noise class. More... | |
| class | GpsSensor |
| GpsSensor to provide position measurement. More... | |
| class | GpuRaySensor |
| GPU based laser sensor. More... | |
| class | ImageGaussianNoiseModel |
| class | ImuSensor |
| An IMU sensor. More... | |
| class | LogicalCameraSensor |
| A camera sensor that reports locations of objects instead of rendering a scene. More... | |
| class | MagnetometerSensor |
| MagnetometerSensor to provide magnetic field measurement. More... | |
| class | MultiCameraSensor |
| Multiple camera sensor. More... | |
| class | Noise |
| Noise models for sensor output signals. More... | |
| class | NoiseFactory |
| Use this noise manager for creating and loading noise models. More... | |
| class | RaySensor |
| Sensor with one or more rays. More... | |
| class | RFIDSensor |
| Sensor class for RFID type of sensor. More... | |
| class | RFIDTag |
| RFIDTag to interact with RFIDTagSensors. More... | |
| class | Sensor |
| Base class for sensors. More... | |
| class | SensorFactory |
| class | SensorManager |
| Class to manage and update all sensors. More... | |
| class | SonarSensor |
| Sensor with sonar cone. More... | |
| class | WideAngleCameraSensor |
| Camera sensor with variable mapping function. More... | |
| class | WirelessReceiver |
| Sensor class for receiving wireless signals. More... | |
| class | WirelessTransceiver |
| Sensor class for receiving wireless signals. More... | |
| class | WirelessTransmitter |
| Transmitter to send wireless signals. More... | |
Enumerations | |
| enum | SensorCategory { IMAGE = 0, RAY = 1, OTHER = 2, CATEGORY_COUNT = 3 } |
| SensorCategory is used to categorize sensors. More... | |
| enum | SensorNoiseType { SENSOR_NOISE_TYPE_BEGIN = 0, NO_NOISE = SENSOR_NOISE_TYPE_BEGIN, CAMERA_NOISE = 1, GPU_RAY_NOISE = 2, GPS_POSITION_LATITUDE_NOISE_METERS = 3, GPS_POSITION_LONGITUDE_NOISE_METERS = 4, GPS_POSITION_ALTITUDE_NOISE_METERS = 5, GPS_VELOCITY_LATITUDE_NOISE_METERS = 6, GPS_VELOCITY_LONGITUDE_NOISE_METERS = 7, GPS_VELOCITY_ALTITUDE_NOISE_METERS = 8, RAY_NOISE = 9, MAGNETOMETER_X_NOISE_TESLA = 10, MAGNETOMETER_Y_NOISE_TESLA = 11, MAGNETOMETER_Z_NOISE_TESLA = 12, ALTIMETER_POSITION_NOISE_METERS = 13, ALTIMETER_VELOCITY_NOISE_METERS_PER_S = 14, IMU_ANGVEL_X_NOISE_RADIANS_PER_S = 15, IMU_ANGVEL_Y_NOISE_RADIANS_PER_S = 16, IMU_ANGVEL_Z_NOISE_RADIANS_PER_S = 17, IMU_LINACC_X_NOISE_METERS_PER_S_SQR = 18, IMU_LINACC_Y_NOISE_METERS_PER_S_SQR = 19, IMU_LINACC_Z_NOISE_METERS_PER_S_SQR = 20, SENSOR_NOISE_TYPE_END } |
Functions | |
| std::string | create_sensor (sdf::ElementPtr _elem, const std::string &_worldName, const std::string &_parentName, uint32_t _parentId) |
| Create a sensor using SDF. More... | |
| void | disable () |
| Disable sensors. More... | |
| void | enable () |
| Enable sensors. More... | |
| bool | fini () |
| shutdown the sensor generation loop. More... | |
| SensorPtr | get_sensor (const std::string &_name) |
| Get a sensor using by name. More... | |
| bool | init () |
| initialize the sensor generation loop. More... | |
| bool | load () |
| Load the sensor library. More... | |
| void | remove_sensor (const std::string &_sensorName) |
| Remove a sensor by name. More... | |
| bool | remove_sensors () |
| Remove all sensors. More... | |
| void | run_once (bool _force=false) |
| Run the sensor generation one step. More... | |
| void | run_threads () |
| Run sensors in a threads. This is a non-blocking call. More... | |
| void | stop () |
| Stop the sensor generation loop. More... | |
Sensors namespace.
| typedef std::vector<AltimeterSensor> AltimeterSensor_V |
| typedef std::shared_ptr<AltimeterSensor> AltimeterSensorPtr |
| typedef std::vector<CameraSensorPtr> CameraSensor_V |
| typedef std::shared_ptr<CameraSensor> CameraSensorPtr |
| typedef std::vector<ContactSensorPtr> ContactSensor_V |
| typedef std::shared_ptr<ContactSensor> ContactSensorPtr |
| typedef std::vector<DepthCameraSensorPtr> DepthCameraSensor_V |
| typedef std::shared_ptr<DepthCameraSensor> DepthCameraSensorPtr |
| typedef std::shared_ptr<ForceTorqueSensor> ForceTorqueSensorPtr |
| typedef std::shared_ptr<GaussianNoiseModel> GaussianNoiseModelPtr |
| typedef std::shared_ptr<GpsSensor> GpsSensorPtr |
| typedef std::vector<GpuRaySensorPtr> GpuRaySensor_V |
| typedef std::shared_ptr<GpuRaySensor> GpuRaySensorPtr |
| typedef std::shared_ptr<ImageGaussianNoiseModel> ImageGaussianNoiseModelPtr |
Shared pointer to Noise.
| typedef std::vector<ImuSensorPtr> ImuSensor_V |
| typedef std::shared_ptr<ImuSensor> ImuSensorPtr |
| typedef std::shared_ptr<LogicalCameraSensor> LogicalCameraSensorPtr |
| typedef std::shared_ptr<MagnetometerSensor> MagnetometerSensorPtr |
| typedef std::vector<MultiCameraSensorPtr> MultiCameraSensor_V |
| typedef std::shared_ptr<MultiCameraSensor> MultiCameraSensorPtr |
| typedef std::vector<RaySensorPtr> RaySensor_V |
| typedef std::shared_ptr<RaySensor> RaySensorPtr |
| typedef std::vector<RFIDSensor> RFIDSensor_V |
| typedef std::shared_ptr<RFIDSensor> RFIDSensorPtr |
| typedef std::shared_ptr<RFIDTag> RFIDTagPtr |
| typedef Sensor*(* SensorFactoryFn)() |
| typedef std::shared_ptr<SonarSensor> SonarSensorPtr |
| typedef std::shared_ptr<WideAngleCameraSensor> WideAngleCameraSensorPtr |
| typedef std::vector<WirelessReceiver> WirelessReceiver_V |
| typedef std::shared_ptr<WirelessReceiver> WirelessReceiverPtr |
| typedef std::vector<WirelessTransceiver> WirelessTransceiver_V |
| typedef std::shared_ptr<WirelessTransceiver> WirelessTransceiverPtr |
| typedef std::vector<WirelessTransmitter> WirelessTransmitter_V |
| typedef std::shared_ptr<WirelessTransmitter> WirelessTransmitterPtr |
| enum 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. |
| enum SensorNoiseType |
| Enumerator | |
|---|---|
| SENSOR_NOISE_TYPE_BEGIN | |
| NO_NOISE |
Noise streams for the Camera sensor.
|
| CAMERA_NOISE |
Noise streams for the Camera sensor.
|
| GPU_RAY_NOISE |
Noise streams for the GPU ray sensor.
|
| GPS_POSITION_LATITUDE_NOISE_METERS |
GPS position latitude noise streams.
|
| GPS_POSITION_LONGITUDE_NOISE_METERS |
GPS position longitude noise streams.
|
| GPS_POSITION_ALTITUDE_NOISE_METERS |
GPS position altitude noise streams.
|
| GPS_VELOCITY_LATITUDE_NOISE_METERS |
GPS velocity latitude noise streams.
|
| GPS_VELOCITY_LONGITUDE_NOISE_METERS |
GPS velocity longitude noise streams.
|
| GPS_VELOCITY_ALTITUDE_NOISE_METERS |
GPS velocity altitude noise streams.
|
| RAY_NOISE |
Noise streams for the ray sensor.
|
| MAGNETOMETER_X_NOISE_TESLA |
Magnetometer body-frame X axis noise in Tesla.
|
| MAGNETOMETER_Y_NOISE_TESLA |
Magnetometer body-frame Y axis noise in Tesla.
|
| MAGNETOMETER_Z_NOISE_TESLA |
Magnetometer body-frame Z axis noise in Tesla.
|
| ALTIMETER_POSITION_NOISE_METERS |
Vertical noise stream for the altimeter sensor.
|
| ALTIMETER_VELOCITY_NOISE_METERS_PER_S |
Velocity noise streams for the altimeter sensor.
|
| IMU_ANGVEL_X_NOISE_RADIANS_PER_S |
IMU angular velocity X noise stream.
|
| IMU_ANGVEL_Y_NOISE_RADIANS_PER_S |
IMU angular velocity Y noise stream.
|
| IMU_ANGVEL_Z_NOISE_RADIANS_PER_S |
IMU angular velocity Z noise stream.
|
| IMU_LINACC_X_NOISE_METERS_PER_S_SQR |
IMU linear acceleration X noise stream.
|
| IMU_LINACC_Y_NOISE_METERS_PER_S_SQR |
IMU linear acceleration Y noise stream.
|
| IMU_LINACC_Z_NOISE_METERS_PER_S_SQR |
IMU linear acceleration Z noise stream.
|
| SENSOR_NOISE_TYPE_END | |