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 #include <assert.h>
00029 #include <math.h>
00030 #include <errno.h>
00031 #include <fcntl.h>
00032 #include <stdio.h>
00033 #include <stdlib.h>
00034 #include <stdint.h>
00035 #include <string.h>
00036 #include <sys/types.h>
00037 #include <sys/stat.h>
00038 #include <ros/ros.h>
00039 #include <sensor_msgs/LaserScan.h>
00040 #include <s3000_laser/SerialDevice.h>
00041
00043 inline double deg_to_rad(double val) { return val*M_PI/180.0; }
00044
00045
00046 class SickS3000
00047 {
00048 public:
00049
00050
00051 SickS3000( std::string port, int baudrate, std::string parity, int datasize );
00052
00053
00054 ~SickS3000();
00055
00057 bool Open();
00058
00060 bool Close();
00061
00063 bool ReadLaser( sensor_msgs::LaserScan& scan );
00064
00065 private:
00066
00067
00068
00069 int ProcessLaserData( sensor_msgs::LaserScan& scan_msg, bool& bValidData );
00070
00071
00072 static unsigned short CreateCRC(const uint8_t *data, ssize_t len);
00073
00074 static bool SetScannerParams(sensor_msgs::LaserScan& scan, int data_count);
00075
00076 protected:
00077
00078
00079 SerialDevice serial_;
00080
00081 bool recognisedScanner;
00082
00083
00084 uint8_t* rx_buffer;
00085 unsigned int rx_buffer_size;
00086 unsigned int rx_count;
00087
00088 static const size_t READ_BUFFER_SIZE=2000;
00089 char read_buffer_[READ_BUFFER_SIZE];
00090 };
00091
00092