chrono::sensor Namespace Reference

Description

Namespace for Chrono::Sensor.

Classes

struct  AccelData
 Accelerometer data. More...
 
struct  Background
 Information about the background of the scene. More...
 
struct  ByteImageData
 stores image data More...
 
class  ChAccelerometerSensor
 Accelerometer class. More...
 
class  ChCameraSensor
 Camera class. More...
 
class  ChDynamicsManager
 class for managing dynamic sensors. More...
 
class  ChFilter
 Base class for all filters that can be applied to a sensor after initial rendering. More...
 
class  ChFilterAccelerometerUpdate
 Class for generating IMU data. More...
 
class  ChFilterAccess
 Filter for accessing data from the sensor. More...
 
class  ChFilterCameraNoiseConstNormal
 A filter that adds Gaussian noise across an image with constant mean and standard deviation. More...
 
class  ChFilterCameraNoisePixDep
 A filter that adds pixel dependent gaussian noise across an image. Method summarized in paper: () More...
 
class  ChFilterGPSUpdate
 Class for generating GPS data for a GPS sensor. More...
 
class  ChFilterGrayscale
 A filter that, when applied to a sensor, changes the RGB buffer to grayscale. More...
 
class  ChFilterGyroscopeUpdate
 Class for generating IMU data. More...
 
class  ChFilterImageHalf4ToRGBA8
 A filter that converts RGBA Float4 to RGBA8. More...
 
class  ChFilterImageResize
 A filter that, when applied to a sensor, resizes the image to the specified dimensions. More...
 
class  ChFilterImgAlias
 A filter that, when applied to a sensor, reduces the resolution for antialiasing. More...
 
class  ChFilterLidarNoiseXYZI
 A filter that adds noise based on depth and intensity given data in point cloud format. More...
 
class  ChFilterMagnetometerUpdate
 Class for generating IMU data. More...
 
class  ChFilterONNX
 A filter that processes data through a pre-trained neural network, based on ONNX format. More...
 
class  ChFilterOptixRender
 A filter that generates data for a ChOptixSensor. More...
 
class  ChFilterPCfromDepth
 A filter that, when applied to a sensor, generates point cloud data from depth values. More...
 
class  ChFilterRadarProcess
 A filter that, when applied to a sensor, converts the depth values to pointcloud, clusters, and calculates velocity and centroid. More...
 
class  ChFilterRadarSavePC
 A filter that, when applied to a sensor, saves point cloud data. More...
 
class  ChFilterSave
 A filter that, when applied to a sensor, saves the data as an image. More...
 
class  ChFilterSavePtCloud
 A filter that, when applied to a sensor, saves point cloud data. More...
 
class  ChFilterUFF
 A filter that processes data through a pre-trained neural network, based on UFF format. More...
 
class  ChFilterVisualize
 A filter that, when applied to a sensor, creates a GUI window to visualize the sensor (using GLFW). More...
 
class  ChFilterVisualizePointCloud
 A filter that, when applied to a sensor, creates a GUI window to visualize the sensor (using GLFW). More...
 
class  ChGPSSensor
 GPS class. More...
 
class  ChGyroscopeSensor
 Gyroscope class. More...
 
class  ChLidarSensor
 Lidar class. This corresponds to a scanning lidar. More...
 
class  ChMagnetometerSensor
 Magnetometer class. More...
 
class  ChNoiseModel
 Noise model base class. More...
 
class  ChNoiseNone
 Noise model: no noise. More...
 
class  ChNoiseNormalDrift
 IMU Noise model: gaussian drifting noise with noncorrelated equal distributions. More...
 
class  ChOptixEngine
 Optix Engine that is responsible for managing all render-based sensors. More...
 
class  ChOptixGeometry
 Optix Geometry class that is responsible for managing all geometric information in the optix scene This handles the acceleration structure and transforms. More...
 
class  ChOptixPipeline
 Class to hold all the Shader Binding Table parameters adnd manage the ray tracing pipeline, materials, ray gen programs. More...
 
class  ChOptixSensor
 Optix sensor class - the base class for all sensors that interface with OptiX to generate and render their data. More...
 
class  ChRadarSensor
 Radar Class/ This corresponds to a fmcw radar. More...
 
class  ChScene
 Scene class used for camera renderings. Includes environment colors, lights, etc. More...
 
class  ChSegmentationCamera
 Camera class. More...
 
class  ChSensor
 Base class for a chrono sensor. A specific sensor can inherit from here. More...
 
class  ChSensorManager
 class for managing sensors. This is the Sensor system class. More...
 
class  ChTachometerSensor
 Tachometer class. This class queries the chrono system for the angular velocity of the parent body. More...
 
struct  GPSData
 GPS data in generic format. More...
 
struct  GyroData
 Gyroscope data. More...
 
class  Logger
 Inference Logger for TensorRT. More...
 
struct  MagnetData
 Magnetometer data. More...
 
struct  PixelDI
 Depth and intensity data in generic format. More...
 
struct  PixelFloat4
 A pixel as defined by RGBA float4 format. More...
 
struct  PixelHalf4
 A pixel as defined by RGBA float4 format. More...
 
struct  PixelRGBA8
 A pixel as defined by RGBA 8bpp format. More...
 
struct  PixelSemantic
 A pixel as defined for semantic segmentation. More...
 
struct  PixelXYZI
 Point cloud and intensity data in generic format. More...
 
struct  ProgramString
 holds string values for ptx file and ray generation program More...
 
class  Sensor
 Sensor class for constructing sensors from a JSON specification file. More...
 
struct  SensorBuffer
 The base buffer class that contains sensor data (contains meta data of the buffer and pointer to raw data) More...
 
struct  SensorBufferT
 Base class of 2D buffers. More...
 
class  SensorConfig
 creates an empty optix transform::node More...
 
struct  Transform
 Transform struct for packing a translation, rotation, and scale. More...
 
struct  TRTDestroyer
 destructor for tensorRT pointers More...
 

Typedefs

using ChFilterR8Access = ChFilterAccess< SensorHostR8Buffer, UserR8BufferPtr >
 Access to greyscale data.
 
using ChFilterRGBA8Access = ChFilterAccess< SensorHostRGBA8Buffer, UserRGBA8BufferPtr >
 Access to RGBA8 data.
 
using ChFilterSemanticAccess = ChFilterAccess< SensorHostSemanticBuffer, UserSemanticBufferPtr >
 Access to semantic image.
 
using ChFilterXYZIAccess = ChFilterAccess< SensorHostXYZIBuffer, UserXYZIBufferPtr >
 Access to point cloud data.
 
using ChFilterDIAccess = ChFilterAccess< SensorHostDIBuffer, UserDIBufferPtr >
 Access to depth/intensity data.
 
using ChFilterAccelAccess = ChFilterAccess< SensorHostAccelBuffer, UserAccelBufferPtr >
 Access to accelerometer data.
 
using ChFilterGyroAccess = ChFilterAccess< SensorHostGyroBuffer, UserGyroBufferPtr >
 Access to gyroscope data.
 
using ChFilterMagnetAccess = ChFilterAccess< SensorHostMagnetBuffer, UserMagnetBufferPtr >
 Access to magnetometer data.
 
using ChFilterGPSAccess = ChFilterAccess< SensorHostGPSBuffer, UserGPSBufferPtr >
 Access to GPS data.
 
using ChFilterRadarAccess = ChFilterAccess< SensorHostRadarBuffer, UserRadarBufferPtr >
 Access to Radar data.
 
using ChFilterRadarXYZAccess = ChFilterAccess< SensorHostRadarXYZBuffer, UserRadarXYZBufferPtr >
 Access to Processed Radar data.
 
using ChFilterTachometerAccess = ChFilterAccess< SensorHostTachometerBuffer, UserTachometerBufferPtr >
 Access to Tachoemter data.
 
using SensorHostFloat4Buffer = SensorBufferT< std::shared_ptr< PixelFloat4[]> >
 RGBA host buffer to be used for managing data on the host.
 
using DeviceFloat4BufferPtr = std::shared_ptr< PixelFloat4[]>
 RGBA device buffer to be used by camera filters in the graph.
 
using SensorDeviceFloat4Buffer = SensorBufferT< DeviceFloat4BufferPtr >
 Sensor buffer wrapper of a DeviceFloat4BufferPtr.
 
using UserFloat4BufferPtr = std::shared_ptr< SensorHostFloat4Buffer >
 pointer to an RGBA image on the host that has been moved for safety and can be given to the user
 
using SensorHostHalf4Buffer = SensorBufferT< std::shared_ptr< PixelHalf4[]> >
 RGBA host buffer to be used for managing data on the host.
 
using DeviceHalf4BufferPtr = std::shared_ptr< PixelHalf4[]>
 RGBA device buffer to be used by camera filters in the graph.
 
using SensorDeviceHalf4Buffer = SensorBufferT< DeviceHalf4BufferPtr >
 Sensor buffer wrapper of a DeviceHalf4BufferPtr.
 
using UserHalf4BufferPtr = std::shared_ptr< SensorHostHalf4Buffer >
 pointer to an RGBA image on the host that has been moved for safety and can be given to the user
 
using SensorHostRGBA8Buffer = SensorBufferT< std::shared_ptr< PixelRGBA8[]> >
 RGBA host buffer to be used for managing data on the host.
 
using DeviceRGBA8BufferPtr = std::shared_ptr< PixelRGBA8[]>
 RGBA device buffer to be used by camera filters in the graph.
 
using SensorDeviceRGBA8Buffer = SensorBufferT< DeviceRGBA8BufferPtr >
 Sensor buffer wrapper of a DeviceRGBA8BufferPtr.
 
using UserRGBA8BufferPtr = std::shared_ptr< SensorHostRGBA8Buffer >
 pointer to an RGBA image on the host that has been moved for safety and can be given to the user
 
using SensorHostR8Buffer = SensorBufferT< std::shared_ptr< char[]> >
 Greyscale host buffer to be used by camera filters in the graph.
 
using DeviceR8BufferPtr = std::shared_ptr< char[]>
 Greyscale device buffer to be used by camera filters in the graph.
 
using SensorDeviceR8Buffer = SensorBufferT< DeviceR8BufferPtr >
 Sensor buffer wrapper of a DeviceR8BufferPtr.
 
using UserR8BufferPtr = std::shared_ptr< SensorHostR8Buffer >
 pointer to a greyscale image on the host that has been moved for safety and can be given to the user
 
using SensorHostSemanticBuffer = SensorBufferT< std::shared_ptr< PixelSemantic[]> >
 Semantic host buffer to be used for managing data on the host.
 
using DeviceSemanticBufferPtr = std::shared_ptr< PixelSemantic[]>
 Semantic device buffer to be used by segmenation camera.
 
using SensorDeviceSemanticBuffer = SensorBufferT< DeviceSemanticBufferPtr >
 Sensor buffer wrapper of a DeviceSemanticBufferPtr.
 
using UserSemanticBufferPtr = std::shared_ptr< SensorHostSemanticBuffer >
 pointer to an semantic image on the host that has been moved for safety and can be given to the user
 
using SensorHostRadarBuffer = RadarBufferT< std::shared_ptr< RadarReturn[]> >
 host buffer to be used by radar filters in the graph
 
using DeviceRadarBufferPtr = std::shared_ptr< RadarReturn[]>
 device buffer to be used by radar filters in the graph
 
using SensorDeviceRadarBuffer = RadarBufferT< DeviceRadarBufferPtr >
 Sensor buffer wrapper of a DeviceRadarBufferPtr.
 
using UserRadarBufferPtr = std::shared_ptr< SensorHostRadarBuffer >
 pointer to a radar buffer on the host that has been moved for safety and can be given to the user
 
using SensorHostRadarXYZBuffer = RadarBufferT< std::shared_ptr< RadarXYZReturn[]> >
 
using DeviceRadarXYZBufferPtr = std::shared_ptr< RadarXYZReturn[]>
 
using SensorDeviceRadarXYZBuffer = RadarBufferT< DeviceRadarXYZBufferPtr >
 
using UserRadarXYZBufferPtr = std::shared_ptr< SensorHostRadarXYZBuffer >
 
using SensorHostDIBuffer = LidarBufferT< std::shared_ptr< PixelDI[]> >
 Depth-intensity host buffer to be used by lidar filters in the graph.
 
using DeviceDIBufferPtr = std::shared_ptr< PixelDI[]>
 Depth-intensity device buffer to be used by lidar filters in the graph.
 
using SensorDeviceDIBuffer = LidarBufferT< DeviceDIBufferPtr >
 Sensor buffer wrapper of a DeviceDIBufferPtr.
 
using UserDIBufferPtr = std::shared_ptr< SensorHostDIBuffer >
 pointer to a depth-intensity buffer on the host that has been moved for safety and can be given to the user
 
using SensorHostXYZIBuffer = LidarBufferT< std::shared_ptr< PixelXYZI[]> >
 Point cloud host buffer to be used by lidar filters in the graph.
 
using DeviceXYZIBufferPtr = std::shared_ptr< PixelXYZI[]>
 Point cloud device buffer to be used by lidar filters in the graph.
 
using SensorDeviceXYZIBuffer = LidarBufferT< DeviceXYZIBufferPtr >
 Sensor buffer wrapper of a DeviceXYZIBufferPtr.
 
using UserXYZIBufferPtr = std::shared_ptr< SensorHostXYZIBuffer >
 pointer to a point cloud buffer on the host that has been moved for safety and can be given to the user
 
using SensorHostAccelBuffer = SensorBufferT< std::shared_ptr< AccelData[]> >
 acclerometer host buffer to be used by acclerometer filters in the graph
 
using UserAccelBufferPtr = std::shared_ptr< SensorHostAccelBuffer >
 pointer to an acclerometer buffer on the host that has been moved for safety and can be given to the user
 
using SensorHostGyroBuffer = SensorBufferT< std::shared_ptr< GyroData[]> >
 acclerometer host buffer to be used by acclerometer filters in the graph
 
using UserGyroBufferPtr = std::shared_ptr< SensorHostGyroBuffer >
 pointer to an acclerometer buffer on the host that has been moved for safety and can be given to the user
 
using SensorHostMagnetBuffer = SensorBufferT< std::shared_ptr< MagnetData[]> >
 acclerometer host buffer to be used by acclerometer filters in the graph
 
using UserMagnetBufferPtr = std::shared_ptr< SensorHostMagnetBuffer >
 pointer to an acclerometer buffer on the host that has been moved for safety and can be given to the user
 
using SensorHostTachometerBuffer = SensorBufferT< std::shared_ptr< TachometerData[]> >
 tachometer host buffer to be used by tachometer filters in the graph
 
using UserTachometerBufferPtr = std::shared_ptr< SensorHostTachometerBuffer >
 pointer to a tachometer buffer on the host that has been moved for safety and can be given to the user
 
using SensorHostGPSBuffer = SensorBufferT< std::shared_ptr< GPSData[]> >
 GPS host buffer to be used by GPS filters in the graph.
 
using UserGPSBufferPtr = std::shared_ptr< SensorHostGPSBuffer >
 pointer to a GPS buffer on the host that has been moved for safety and can be given to the user
 

Enumerations

enum  PipelineType {
  PipelineType::CAMERA_PINHOLE, PipelineType::CAMERA_FOV_LENS, PipelineType::SEGMENTATION_PINHOLE, PipelineType::SEGMENTATION_FOV_LENS,
  PipelineType::LIDAR_SINGLE, PipelineType::LIDAR_MULTI, PipelineType::RADAR
}
 The type of ray tracing used to model the sensor. More...
 
enum  CameraLensModelType { CameraLensModelType::PINHOLE, CameraLensModelType::FOV_LENS }
 The type of lens model that camera can use for rendering. More...
 
enum  LidarReturnMode {
  LidarReturnMode::STRONGEST_RETURN, LidarReturnMode::MEAN_RETURN, LidarReturnMode::FIRST_RETURN, LidarReturnMode::LAST_RETURN,
  LidarReturnMode::DUAL_RETURN
}
 Lidar return mode when multiple objects are seen. More...
 
enum  Axis { X, Y, Z }
 
enum  LoggerVerbosity { NONE, PARTIAL, ALL }
 Logger verbosity enumerator. More...
 

Functions

void cuda_camera_noise_const_normal (unsigned char *bufPtr, int width, int height, float mean, float stdev, curandState_t *rng, CUstream &stream)
 Kernel for applying uniform Gaussian noise to an image. More...
 
void cuda_camera_noise_pixel_dependent (unsigned char *bufPtr, int width, int height, float gain, float sigma_read, float sigma_adc, curandState_t *rng, CUstream &stream)
 Kernel for applying pixel dependent Gaussian noise to an image. More...
 
__global__ void init_random_states (unsigned int seed, curandState_t *rng_states, int n_generators)
 Device function for initialing random values for cuRAND. More...
 
void init_cuda_rng (unsigned int seed, curandState_t *rng_states, int n_generators)
 Host function for initialing random values for cuRAND. More...
 
void cuda_grayscale (void *bufRGBA, void *bufOut, int width, int height, CUstream &stream)
 RGB 8 bpp image of uchar to greyscale image conversion. More...
 
void cuda_image_alias (void *bufIn, void *bufOut, int w_out, int h_out, int factor, int pix_size, CUstream &stream)
 An antialiasing helper function that reduces image quality by performing mean reduction of image. More...
 
void cuda_image_alias_float (void *bufIn, void *bufOut, int w_out, int h_out, int factor, int pix_size, CUstream &stream)
 An antialiasing helper function that reduces image quality by performing mean reduction of image. More...
 
void cuda_image_gauss_blur_char (void *buf, int w, int h, int c, int factor, CUstream &stream)
 An image blurring function that reduces performs Gaussian blur. More...
 
void cuda_image_half4_to_uchar4 (void *bufIn, void *bufOut, int w, int h, CUstream &stream)
 Conversion from half4 to uchar4. More...
 
void cuda_lidar_clip (float *buf, int width, int height, float threshold, float default_dist, CUstream &stream)
 Function for reduction of data when multiple samples are used per beam. More...
 
void cuda_lidar_noise_normal (float *bufPtr, int width, int height, float stdev_range, float stdev_v_angle, float stdev_h_angle, float stdev_intensity, curandState_t *rng, CUstream &stream)
 Function for applying Gaussian noise to raw ground truth lidar data. More...
 
void cuda_lidar_mean_reduce (void *bufIn, void *bufOut, int width, int height, int radius, CUstream &stream)
 Function for reduction of data when multiple samples are used per beam. More...
 
void cuda_lidar_strong_reduce (void *bufIn, void *bufOut, int width, int height, int radius, CUstream &stream)
 Function for reduction of data when multiple samples are used per beam. More...
 
void cuda_lidar_first_reduce (void *bufIn, void *bufOut, int width, int height, int radius, CUstream &stream)
 Function for reduction of data when multiple samples are used per beam. More...
 
void cuda_lidar_dual_reduce (void *bufIn, void *bufOut, int width, int height, int radius, CUstream &stream)
 Function for reduction of data when multiple samples are used per beam. More...
 
void preprocess_RGBA8_to_FLOAT3 (void *bufIn, void *bufOut, int h, int w)
 Function that converts uchar RGBA8 image to float3 image. More...
 
void preprocess_RGBA8_to_FLOAT4 (void *bufIn, void *bufOut, int num_entries)
 Function that converts uchar RGBA8 image to float4 image. More...
 
void postprocess_FLOAT4_to_RGBA8 (void *bufIn, void *bufOut, int num_entries)
 Function that converts float4 image to uchar RGBA8 image. More...
 
void preprocess_RGBA8_to_FLOAT4_CHW (void *bufIn, void *bufOut, int c, int h, int w)
 Function that converts uchar RGBA8 image to float4 image with channels first. More...
 
void preprocess_normalize_float (void *bufIn, float add, float mult, int c, int h, int w)
 Function that normalized input data in float format. More...
 
void postprocess_FLOAT4_to_RGBA8_CHW (void *bufIn, void *bufOut, int c, int h, int w)
 Function that converts float4 image to uchar RGBA8 image with channels first. More...
 
void cuda_pointcloud_from_depth (void *bufDI, void *bufOut, int width, int height, float hfov, float max_v_angle, float min_v_angle, CUstream &stream)
 Converts depth data to point cloud data for a lidar. More...
 
void cuda_pointcloud_from_depth_dual_return (void *bufDI, void *bufOut, int width, int height, float hfov, float max_v_angle, float min_v_angle, CUstream &stream)
 Converts depth data to point cloud data for a lidar when the mode is dual return. More...
 
void cuda_radar_angles (void *bufIn, void *bufOut, int width, int height, float hfov, float vfov, CUstream &stream)
 
void cuda_radar_pointcloud_from_angles (void *bufIn, void *bufOut, int width, int height, float hfov, float vfov, CUstream &stream)
 
void cuda_radar_pointcloud_from_depth (void *bufDI, void *bufOut, int width, int height, float hfov, float vfov, CUstream &stream)
 
void SetSensorShaderDir (std::string path)
 
void GetShaderFromFile (OptixDeviceContext context, OptixModule &module, std::string file_name, OptixModuleCompileOptions &module_compile_options, OptixPipelineCompileOptions &pipeline_compile_options)
 launches ray generation program More...
 
void optix_log_callback (unsigned int level, const char *tag, const char *message, void *)
 
ByteImageData LoadByteImage (std::string filename)
 loads image to struct ByteImageData, returns an empty struct with 0 values if loading failed More...
 
void Cartesian2GPS (ChVector< double > &coords, ChVector< double > &ref)
 Utility function for calculating Cartesian coordinates from GPS coordinates given the simulation's reference point. More...
 
void GPS2Cartesian (ChVector< double > &coords, ChVector< double > &ref)
 Utility function for calculating GPS coordinates from Cartesian coordinates given the simulation's reference point. More...
 
void ReadFileJSON (const std::string &filename, Document &d)
 
ChVector ReadVectorJSON (const Value &a)
 
ChQuaternion ReadQuaternionJSON (const Value &a)
 
ChFrame ReadFrameJSON (const Value &a)
 
std::shared_ptr< ChSensorReadSensorJSON (const std::string &filename, std::shared_ptr< chrono::ChBody > parent, chrono::ChFrame< double > offsetPose)
 Load and return a sensor from the specified JSON file. More...
 
std::shared_ptr< ChCameraSensorReadCameraSensorJSON (const std::string &filename, std::shared_ptr< chrono::ChBody > parent, chrono::ChFrame< double > offsetPose)
 Load and return a camera sensor from the specified JSON file. More...
 
std::shared_ptr< ChGPSSensorReadGPSSensorJSON (const std::string &filename, std::shared_ptr< chrono::ChBody > parent, chrono::ChFrame< double > offsetPose)
 Load and return a gps sensor from the specified JSON file. More...
 
std::shared_ptr< ChAccelerometerSensorReadAccelerometerSensorJSON (const std::string &filename, std::shared_ptr< chrono::ChBody > parent, chrono::ChFrame< double > offsetPose)
 Load and return a accelerometer sensor from the specified JSON file. More...
 
std::shared_ptr< ChGyroscopeSensorReadGyroscopeSensorJSON (const std::string &filename, std::shared_ptr< chrono::ChBody > parent, chrono::ChFrame< double > offsetPose)
 Load and return a gyroscope sensor from the specified JSON file. More...
 
std::shared_ptr< ChMagnetometerSensorReadMagnetometerSensorJSON (const std::string &filename, std::shared_ptr< chrono::ChBody > parent, chrono::ChFrame< double > offsetPose)
 Load and return a magnetometer sensor from the specified JSON file. More...
 
std::shared_ptr< ChLidarSensorReadLidarSensorJSON (const std::string &filename, std::shared_ptr< chrono::ChBody > parent, chrono::ChFrame< double > offsetPose)
 Load and return a lidar sensor from the specified JSON file. More...
 
std::shared_ptr< ChRadarSensorReadRadarSensorJSON (const std::string &filename, std::shared_ptr< chrono::ChBody > parent, chrono::ChFrame< double > offsetPose)
 Load and return a radar sensor from the specified JSON file. More...
 
void ReadFilterListJSON (const std::string &filename, std::shared_ptr< ChSensor > sensor)
 Load and return a sensor filter list from the specified JSON file. More...
 
std::shared_ptr< ChFilterCreateFilterJSON (const Value &value)
 
std::shared_ptr< ChNoiseModelCreateNoiseJSON (const Value &value)
 
std::string GetStringMemberWithDefault (const Value &value, const char *member, const char *def)
 
CH_SENSOR_API void ReadFileJSON (const std::string &filename, rapidjson::Document &d)
 Load and return a RapidJSON document from the specified file. More...
 
CH_SENSOR_API ChVector ReadVectorJSON (const rapidjson::Value &a)
 Load and return a ChVector from the specified JSON array. More...
 
CH_SENSOR_API ChQuaternion ReadQuaternionJSON (const rapidjson::Value &a)
 Load and return a ChQuaternion from the specified JSON array. More...
 
CH_SENSOR_API ChFrame ReadFrameJSON (const rapidjson::Value &a)
 Load and return a ChFrame from the specified JSON array. More...
 
CH_SENSOR_API std::shared_ptr< ChFilterCreateFilterJSON (const rapidjson::Value &value)
 Load and return a sensor filter from the specified JSON value. More...
 
CH_SENSOR_API std::shared_ptr< ChNoiseModelCreateNoiseJSON (const rapidjson::Value &value)
 Load and return a noise model from the specified JSON value. More...
 
CH_SENSOR_API std::string GetStringMemberWithDefault (const rapidjson::Value &value, const char *member, const char *def="")
 Load and return a std::string from the specified JSON value Will check if member exists and returns if it does, def if not. More...
 
void CreateModernMeshAssets (std::shared_ptr< ChTriangleMeshShape > mesh_shape)
 Generate a set of visual assets that works with OptiX and handles the most modern rendering information contained in the mesh as possible. More...
 
void ConvertToModernAssets (std::shared_ptr< ChBody > body)
 Convert assets attached to a ChBody to modern assets by creating all necessary parameters for reflections, refractions, etc. More...
 
void ConvertToModernAssets (ChSystem *sys)
 Parse all assets of a chrono system to do a full conversion to assets needed by OptiX. More...
 
template<class T >
T * cudaMallocHelper (unsigned int size)
 Function for creating a chunk of memory that will implicitely desconstruct itself. More...
 
template<class T >
void cudaFreeHelper (T *ptr)
 The desconstructor that will be called to free memory from the device pointer. More...
 
template<class T >
T * cudaHostMallocHelper (unsigned int size)
 Function for creating a chunk of memory that will implicitely desconstruct itself. More...
 
template<class T >
void cudaHostFreeHelper (T *ptr)
 The desconstructor that will be called to free memory from the device pointer. More...
 

Variables

const char ChFilterR8AccessName [] = "ChFilterR8Access"
 global constanst for use in template parameters
 
const char ChFilterRGBA8AccessName [] = "ChFilterRGBA8Access"
 single channel 8 bit array
 
const char ChFilterDIAccessName [] = "ChFilterDIAccess"
 4 channel 8 bit array
 
const char ChFilterXYZIAccessName [] = "ChFilterXYZIAccess"
 2 channel float array (Depth+Intenisty)
 
const char ChFilterAccelAccessName [] = "ChFilterAccelAccess"
 4 channel float array (XYZ positions+Intensity)
 
const char ChFilterGyroAccessName [] = "ChFilterGyroAccess"
 Accelerometer data format (3 doubles total)
 
const char ChFilterMagnetAccessName [] = "ChFilterMagnetAccess"
 Gyroscope data format (3 doubles total)
 
const char ChFilterGPSAccessName [] = "ChFilterGPSAccess"
 Magnetometer data format (3 doubles total)
 
const char ChFilterRadarAccessName [] = "ChFilterRadarAccess"
 GPS data format (4 doubles total)
 
const char ChFilterRadarXYZAccessName [] = "ChFilterRadarXYZAccess"
 
const char ChFilterTachometerAccessName [] = "ChFilterTachometerAccess"
 

Function Documentation

◆ Cartesian2GPS()

CH_SENSOR_API void chrono::sensor::Cartesian2GPS ( ChVector< double > &  coords,
ChVector< double > &  ref 
)

Utility function for calculating Cartesian coordinates from GPS coordinates given the simulation's reference point.

Parameters
coordsThe Cartisian coordinates to be modified. This ChVector is modified and used as output
refThe simulation's reference location

◆ GPS2Cartesian()

CH_SENSOR_API void chrono::sensor::GPS2Cartesian ( ChVector< double > &  coords,
ChVector< double > &  ref 
)

Utility function for calculating GPS coordinates from Cartesian coordinates given the simulation's reference point.

Parameters
coordsThe GPS coordinates to be modified. This ChVector is modified and used as output
refThe simulation's reference location