Gazebo Sensors

API Reference

9.0.0~pre2
SensorTypes.hh File Reference

Forward declarations and typedefs for sensors. More...

#include <vector>
#include <memory>
#include <gz/common/EnumIface.hh>
#include <gz/sensors/config.hh>
#include <gz/sensors/Export.hh>

Go to the source code of this file.

Namespaces

namespace  gz
 
namespace  gz::sensors
 Sensors namespace.
 

Typedefs

typedef std::shared_ptr< BrownDistortionModelBrownDistortionModelPtr
 
typedef std::vector< CameraSensorPtrCameraSensor_V
 
typedef std::shared_ptr< CameraSensorCameraSensorPtr
 
typedef std::shared_ptr< DistortionDistortionPtr
 
typedef std::shared_ptr< GaussianNoiseModelGaussianNoiseModelPtr
 
typedef std::vector< GpuLidarSensorPtrGpuLidarSensor_V
 
typedef std::shared_ptr< GpuLidarSensorGpuLidarSensorPtr
 
typedef std::shared_ptr< ImageBrownDistortionModelImageBrownDistortionModelPtr
 
typedef std::shared_ptr< ImageGaussianNoiseModelImageGaussianNoiseModelPtr
 Shared pointer to Noise.
 
typedef std::shared_ptr< NoiseNoisePtr
 
typedef std::vector< SensorPtrSensor_V
 
typedef std::shared_ptr< SensorSensorPtr
 

Enumerations

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  SensorDistortionType { SENSOR_DISTORTION_TYPE_BEGIN = 0 , NO_DISTORTION = SENSOR_DISTORTION_TYPE_BEGIN , CAMERA_DISTORTION = 1 , SENSOR_DISTORTION_TYPE_END }
 
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 ,
  FORCE_X_NOISE_N = 15 , FORCE_Y_NOISE_N = 16 , FORCE_Z_NOISE_N = 17 , TORQUE_X_NOISE_N_M = 18 ,
  TORQUE_Y_NOISE_N_M = 19 , TORQUE_Z_NOISE_N_M = 20 , NAVSAT_HORIZONTAL_POSITION_NOISE = 21 , NAVSAT_VERTICAL_POSITION_NOISE = 22 ,
  NAVSAT_HORIZONTAL_VELOCITY_NOISE = 23 , NAVSAT_VERTICAL_VELOCITY_NOISE = 24 , AIR_SPEED_NOISE_PASCALS = 25 , SENSOR_NOISE_TYPE_END
}
 

Detailed Description

Forward declarations and typedefs for sensors.