RangeSensor.h
Go to the documentation of this file.
1 
7 #ifndef RANGESENSOR_H_
8 #define RANGESENSOR_H_
9 
10 #include <opencv2/opencv.hpp>
11 #include <opencv2/imgproc/imgproc.hpp>
12 #include <vector>
13 #include <memory>
14 #include <pses_simulation/RangeSensorConfig.h>
15 #include <nav_msgs/MapMetaData.h>
16 
23 namespace rs
24 {
30 typedef std::shared_ptr<std::vector<float>> rangeArray_ptr;
36 {
38  us
39 };
40 
51 double correctYawAngle(const double theta, const double increment);
57 const int sgn(const int x);
63 double degToRad(double angle);
69 double radToDeg(double angle);
70 
71 class RangeSensor;
72 }
73 
74 using rs::RangeSensor;
85 {
86 public:
92  RangeSensor(const SensorType& type);
98  void setConfig(pses_simulation::RangeSensorConfig& config);
104  void setMap(const cv::Mat& map);
115  void setMapMetaData(const nav_msgs::MapMetaData& mapInfo);
123  const rs::rangeArray_ptr getLaserScan(const cv::Point sensorPos,
124  const double theta) const;
133  const double getUSScan(const cv::Point sensorPos, const double theta) const;
134 
135 private:
149  pses_simulation::RangeSensorConfig config;
156  cv::Mat map;
163  nav_msgs::MapMetaData mapInfo;
164 };
165 
166 #endif /* RANGESENSOR_H_ */
The rs::RangeSensor class simulates different range finder sensors based on the given rs::SensorType ...
pses_simulation::RangeSensorConfig config
Definition: RangeSensor.h:149
nav_msgs::MapMetaData mapInfo
Definition: RangeSensor.h:163
nav_msgs::MapMetaData mapInfo
occupancy grid meta data
cv::Mat map
Definition: RangeSensor.h:156
rs::SensorType type
rs::SensorType enumerator
This namespace groups typedefs and enums used in the rs::RangeSensor class and the rs::RangeSensor cl...
SensorType
Enumerator for supported sensor types.
Definition: RangeSensor.h:35
std::shared_ptr< std::vector< float > > rangeArray_ptr
shortcut for a pointer to a vector of floats representing range readings in meters.
Definition: RangeSensor.h:30
double radToDeg(double angle)
Conversion from radiants to degrees.
Definition: RangeSensor.cpp:35
const int sgn(const int x)
Get the sign of an interger.
Definition: RangeSensor.cpp:31
rs::SensorType type
Definition: RangeSensor.h:142
double degToRad(double angle)
Conversion from degrees to radiants.
Definition: RangeSensor.cpp:33
pses_simulation::RangeSensorConfig config
dynamic reconfigure object for this sensor
cv::Mat map
occupancy grid represented by a monochromatic image
double correctYawAngle(const double theta, const double increment)
Calculate a correct euler angle after incrementing/decrementing.
Definition: RangeSensor.cpp:12


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