Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef SICK_GENERIC_RADAR_H_
00038 #define SICK_GENERIC_RADAR_H_
00039
00040 #include <stdio.h>
00041 #include <stdlib.h>
00042 #include <string>
00043 #include <string.h>
00044 #include <vector>
00045
00046 #include <ros/ros.h>
00047 #include <sensor_msgs/LaserScan.h>
00048 #include <sensor_msgs/PointCloud.h>
00049 #include <sensor_msgs/PointCloud2.h>
00050 #include <std_msgs/String.h>
00051
00052 #include <diagnostic_updater/diagnostic_updater.h>
00053 #include <diagnostic_updater/publisher.h>
00054 #include <sick_scan/sick_scan_common_nw.h>
00055 #include <sick_scan/RadarScan.h>
00056
00057 #ifndef _MSC_VER
00058 #include <dynamic_reconfigure/server.h>
00059 #include <sick_scan/SickScanConfig.h>
00060 #endif
00061 #include "sick_scan/sick_generic_parser.h"
00062 #include "sick_scan/sick_scan_common_nw.h"
00063
00064 namespace sick_scan
00065 {
00066
00067 class SickScanRadarRawTarget
00068 {
00069 public:
00070 float Dist() const { return dist; }
00071 void Dist(float val) { dist = val; }
00072 float Azimuth() const { return azimuth; }
00073 void Azimuth(float val) { azimuth = val; }
00074 float Vrad() const { return vrad; }
00075 void Vrad(float val) { vrad = val; }
00076 float Ampl() const { return ampl; }
00077 void Ampl(float val) { ampl = val; }
00078 int Mode() const { return mode; }
00079 void Mode(int val) { mode = val; }
00080 private:
00081 float dist;
00082 float azimuth;
00083 float vrad;
00084 float ampl;
00085 int mode;
00086 };
00087
00088 class SickScanRadarObject
00089 {
00090 public:
00091 float P3Dx() const { return p3Dx; }
00092 void P3Dx(float val) { p3Dx = val; }
00093 float P3Dy() const { return p3Dy; }
00094 void P3Dy(float val) { p3Dy = val; }
00095 float V3Dx() const { return v3Dx; }
00096 void V3Dx(float val) { v3Dx = val; }
00097 float V3Dy() const { return v3Dy; }
00098 void V3Dy(float val) { v3Dy = val; }
00099 float ObjLength() const { return objLength; }
00100 void ObjLength(float val) { objLength = val; }
00101
00102 int ObjId() const { return objId; }
00103 void ObjId(int val) { objId = val; }
00104 private:
00105 float p3Dx;
00106 float p3Dy;
00107 float v3Dx;
00108 float v3Dy;
00109 float objLength;
00110 int objId;
00111 };
00112
00113
00114 class SickScanRadar
00115 {
00116 public:
00117 SickScanRadar(SickScanCommon *commonPtr_)
00118 {
00119 commonPtr = commonPtr_;
00120 }
00121 void setEmulation(bool _emul);
00122 bool getEmulation(void);
00123 int parseDatagram(ros::Time timeStamp, unsigned char *receiveBuffer, int actual_length, bool useBinaryProtocol);
00124 int parseAsciiDatagram(char* datagram, size_t datagram_length, sick_scan::RadarScan *msgPtr, std::vector<SickScanRadarObject> &objectList, std::vector<SickScanRadarRawTarget> &rawTargetList);
00125 void simulateAsciiDatagram(unsigned char * receiveBuffer, int* actual_length);
00126 private:
00127 SickScanCommon *commonPtr;
00128 void simulateAsciiDatagramFromFile(unsigned char *receiveBuffer, int *actual_length, std::string filePattern);
00129 bool emul;
00130 };
00131
00132 }
00133 #endif // SICK_GENERIC_RADAR_H_