Public Member Functions | Private Attributes | List of all members
RangeSensor Class Reference

#include <RangeSensor.h>

Public Member Functions

const rs::rangeArray_ptr getLaserScan (const cv::Point sensorPos, const double theta) const
 Get a Laserscan at the current position/orientation. More...
 
const double getUSScan (const cv::Point sensorPos, const double theta) const
 Get a ultra sonic range information at the current position/orientation. More...
 
 RangeSensor (const SensorType &type)
 rs::RangeSensor constructor. More...
 
void setConfig (pses_simulation::RangeSensorConfig &config)
 Sets the RangeSensorConfig object of this sensor simulation. More...
 
void setMap (const cv::Mat &map)
 Sets the occupancy grid to be used by this sensor simulation. More...
 
void setMapMetaData (const nav_msgs::MapMetaData &mapInfo)
 Sets the meta data of the occupancy grid to be used by this sensor simulation. More...
 

Private Attributes

pses_simulation::RangeSensorConfig config
 
cv::Mat map
 
nav_msgs::MapMetaData mapInfo
 
rs::SensorType type
 

Detailed Description

Definition at line 84 of file RangeSensor.h.

Constructor & Destructor Documentation

RangeSensor::RangeSensor ( const SensorType &  type)

rs::RangeSensor constructor.

Parameters
[in]typedefines what kind of range finder will be simulated.

Definition at line 38 of file RangeSensor.cpp.

Member Function Documentation

const rs::rangeArray_ptr RangeSensor::getLaserScan ( const cv::Point  sensorPos,
const double  theta 
) const

Get a Laserscan at the current position/orientation.

Parameters
[in]sensorPossensor position
[in]thetasensor orientation in a plane
Returns
array of range finder values in meters

Definition at line 52 of file RangeSensor.cpp.

const double RangeSensor::getUSScan ( const cv::Point  sensorPos,
const double  theta 
) const

Get a ultra sonic range information at the current position/orientation.

Parameters
[in]sensorPossensor position
[in]thetasensor orientation in a plane
Returns
range finder value in meters

Definition at line 110 of file RangeSensor.cpp.

void RangeSensor::setConfig ( pses_simulation::RangeSensorConfig &  config)

Sets the RangeSensorConfig object of this sensor simulation.

Parameters
[in]configdynamic reconfigure object for this sensor

Definition at line 40 of file RangeSensor.cpp.

void RangeSensor::setMap ( const cv::Mat &  map)

Sets the occupancy grid to be used by this sensor simulation.

Parameters
[in]mapoccupancy grid represented by a monochromatic image

Definition at line 45 of file RangeSensor.cpp.

void RangeSensor::setMapMetaData ( const nav_msgs::MapMetaData &  mapInfo)

Sets the meta data of the occupancy grid to be used by this sensor simulation.

Meta data contains information about the occupancy grids resultion, point of origin and meaning of grid values.

Parameters
[in]mapInfooccupancy grid meta data

Definition at line 47 of file RangeSensor.cpp.

Member Data Documentation

pses_simulation::RangeSensorConfig RangeSensor::config
private

Definition at line 149 of file RangeSensor.h.

cv::Mat RangeSensor::map
private

Definition at line 156 of file RangeSensor.h.

nav_msgs::MapMetaData RangeSensor::mapInfo
private

Definition at line 163 of file RangeSensor.h.

rs::SensorType RangeSensor::type
private

Definition at line 142 of file RangeSensor.h.


The documentation for this class was generated from the following files:


pses_simulation
Author(s): Sebastian Ehmes
autogenerated on Wed Dec 13 2017 19:37:54