37 #ifndef SICK_GENERIC_FIELD_MON_H_ 38 #define SICK_GENERIC_FIELD_MON_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> 101 static void rectangularFieldToCarthesian(
float distRefPointMeter,
float angleRefPointRad,
float rotAngleRad,
float rectWidthMeter,
float rectLengthMeter,
float points_x[4],
float points_y[4]);
118 static void dynamicFieldPointToCarthesian(
float distRefPointMeter,
float angleRefPointRad,
float rotAngleRad,
float rectWidthMeter,
float rectLengthMeter,
float maxSpeedMeterPerSec,
float maxLengthMeter,
float points_x[8],
float points_y[8]);
131 m_fieldPoints_X.push_back(x);
132 m_fieldPoints_Y.push_back(y);
137 assert(m_fieldPoints_X.size() == m_fieldPoints_Y.size());
138 return m_fieldPoints_X.size();
169 const std::vector<SickScanMonField>&
getMonFields(
void)
const {
return monFields; }
174 int parseAsciiLIDinputstateMsg(
unsigned char* datagram,
int datagram_length);
175 int parseBinaryLIDinputstateMsg(
unsigned char* datagram,
int datagram_length);
177 int parseBinaryDatagram(std::vector<unsigned char> datagramm);
179 int parseAsciiDatagram(std::vector<unsigned char> datagramm);
189 commonPtr = commonPtr_;
191 void setEmulation(
bool _emul);
192 bool getEmulation(
void);
193 int parseDatagram(
ros::Time timeStamp,
unsigned char *receiveBuffer,
int actual_length,
bool useBinaryProtocol);
194 int parseAsciiDatagram(
char* datagram,
size_t datagram_length, sick_scan::RadarScan *msgPtr, std::vector<SickScanRadarObject> &objectList, std::vector<SickScanRadarRawTarget> &rawTargetList);
195 void simulateAsciiDatagram(
unsigned char * receiveBuffer,
int* actual_length);
198 void simulateAsciiDatagramFromFile(
unsigned char *receiveBuffer,
int *actual_length, std::string filePattern);
204 #endif // SICK_GENERIC_RADAR_H_
const std::vector< SickScanMonField > & getMonFields(void) const
const std::vector< float > & getFieldPointsX(void) const
TFSIMD_FORCE_INLINE const tfScalar & y() const
std::vector< SickScanMonField > monFields
const std::vector< float > & getFieldPointsY(void) const
int getActiveFieldset(void)
std::vector< float > m_fieldPoints_X
static void rectangularFieldToCarthesian(float distRefPointMeter, float angleRefPointRad, float rotAngleRad, float rectWidthMeter, float rectLengthMeter, float points_x[4], float points_y[4])
int getPointCount(void) const
static void dynamicFieldPointToCarthesian(float distRefPointMeter, float angleRefPointRad, float rotAngleRad, float rectWidthMeter, float rectLengthMeter, float maxSpeedMeterPerSec, float maxLengthMeter, float points_x[8], float points_y[8])
static void segmentedFieldPointToCarthesian(float range, float angle_rad, float &x, float &y)
TFSIMD_FORCE_INLINE const tfScalar & x() const
SickScanMonFieldType & fieldType(void)
void pushFieldPointCarthesian(float x, float y)
std::vector< float > m_fieldPoints_Y
void setActiveFieldset(int active_fieldset)
ros::Publisher chatter_pub
const SickScanMonFieldType & fieldType(void) const
static SickScanFieldMonSingleton * instance