Go to the documentation of this file.
59 #ifndef SICK_GENERIC_RADAR_H_
60 #define SICK_GENERIC_RADAR_H_
204 int parseRadarDatagram(
char* datagram,
size_t datagram_length,
bool useBinaryProtocol,
206 std::vector<SickScanRadarObject>& objectList,
207 std::vector<SickScanRadarRawTarget>& rawTargetList,
208 int verboseLevel = 0);
227 SickScanRadar(SickScanCommon *commonPtr_)
229 commonPtr = commonPtr_;
231 void setEmulation(
bool _emul);
232 bool getEmulation(
void);
233 int parseDatagram(
rosTime timeStamp,
unsigned char *receiveBuffer,
int actual_length,
bool useBinaryProtocol);
234 int parseAsciiDatagram(
char* datagram,
size_t datagram_length,
sick_scan_msg::RadarScan *msgPtr, std::vector<SickScanRadarObject> &objectList, std::vector<SickScanRadarRawTarget> &rawTargetList);
235 void simulateAsciiDatagram(
unsigned char * receiveBuffer,
int* actual_length);
238 void simulateAsciiDatagramFromFile(
unsigned char *receiveBuffer,
int *actual_length, std::string filePattern);
244 #endif // SICK_GENERIC_RADAR_H_
void setNameOfRadar(const std::string &_radarName, RADAR_TYPE_ENUM _radarType)
sick_scan_xd::SickRangeFilter m_range_filter
rosPublisher< sick_scan_msg::RadarScan > radarScan_pub_
static SickScanRadarSingleton * instance
rosPublisher< ros_sensor_msgs::PointCloud2 > cloud_radar_rawtarget_pub_
int parseRadarDatagram(char *datagram, size_t datagram_length, bool useBinaryProtocol, sick_scan_msg::RadarScan *msgPtr, std::vector< SickScanRadarObject > &objectList, std::vector< SickScanRadarRawTarget > &rawTargetList, int verboseLevel=0)
Parsing Ascii datagram.
void ObjLength(float val)
int parseDatagram(rosTime timeStamp, unsigned char *receiveBuffer, int actual_length, bool useBinaryProtocol)
sick_scan_xd::SickCloudTransform m_add_transform_xyz_rpy
static SickScanRadarSingleton * getInstance(rosNodePtr nh)
std::string getNameOfRadar()
void simulateAsciiDatagram(unsigned char *receiveBuffer, int *actual_length)
void simulateAsciiDatagramFromFile(unsigned char *receiveBuffer, int *actual_length, std::string filePattern)
void setEmulation(bool _emul)
::sick_scan_xd::RadarScan_< std::allocator< void > > RadarScan
ros::Time * timeStamp(M &m)
returns TimeStamp<M>::pointer(m);
RADAR_TYPE_ENUM radarType
SickScanRadarSingleton(rosNodePtr nh)
rosPublisher< ros_sensor_msgs::PointCloud2 > cloud_radar_track_pub_
sick_scan_xd
Author(s): Michael Lehning
, Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:10