37 #ifndef SICK_GENERIC_RADAR_H_ 38 #define SICK_GENERIC_RADAR_H_ 47 #include <sensor_msgs/LaserScan.h> 48 #include <sensor_msgs/PointCloud.h> 49 #include <sensor_msgs/PointCloud2.h> 50 #include <std_msgs/String.h> 55 #include <sick_scan/RadarScan.h> 59 #include <dynamic_reconfigure/server.h> 60 #include <sick_scan/SickScanConfig.h> 139 {
return objLength; }
169 void simulateAsciiDatagramFromFile(
unsigned char *receiveBuffer,
int *actual_length, std::string filePattern);
184 void setEmulation(
bool _emul);
186 bool getEmulation(
void);
188 int parseDatagram(
ros::Time timeStamp,
unsigned char *receiveBuffer,
int actual_length,
bool useBinaryProtocol);
190 int parseAsciiDatagram(
char *datagram,
size_t datagram_length, sick_scan::RadarScan *msgPtr,
191 std::vector<SickScanRadarObject> &objectList,
192 std::vector<SickScanRadarRawTarget> &rawTargetList);
193 void simulateAsciiDatagram(
unsigned char *receiveBuffer,
int *actual_length);
203 commonPtr = commonPtr_;
205 void setEmulation(
bool _emul);
206 bool getEmulation(
void);
207 int parseDatagram(
ros::Time timeStamp,
unsigned char *receiveBuffer,
int actual_length,
bool useBinaryProtocol);
208 int parseAsciiDatagram(
char* datagram,
size_t datagram_length, sick_scan::RadarScan *msgPtr, std::vector<SickScanRadarObject> &objectList, std::vector<SickScanRadarRawTarget> &rawTargetList);
209 void simulateAsciiDatagram(
unsigned char * receiveBuffer,
int* actual_length);
212 void simulateAsciiDatagramFromFile(
unsigned char *receiveBuffer,
int *actual_length, std::string filePattern);
218 #endif // SICK_GENERIC_RADAR_H_
ros::Publisher cloud_radar_rawtarget_pub_
static SickScanRadarSingleton * instance
ros::Publisher radarScan_pub_
ros::Publisher cloud_radar_track_pub_
void ObjLength(float val)
ros::Publisher chatter_pub