sicks3000.h
Go to the documentation of this file.
00001 /*
00002 *  Copyright (c) 2012, Robotnik Automation, SLL
00003 *
00004 *
00005 *   This program is free software: you can redistribute it and/or modify
00006 *   it under the terms of the GNU General Public License as published by
00007 *   the Free Software Foundation, either version 3 of the License, or
00008 *   (at your option) any later version.
00009 *
00010 *   This program is distributed in the hope that it will be useful,
00011 *   but WITHOUT ANY WARRANTY; without even the implied warranty of
00012 *   MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00013 *   GNU General Public License for more details.
00014 *
00015 *   You should have received a copy of the GNU General Public License
00016 *   along with this program.  If not, see <http://www.gnu.org/licenses/>.
00017 *
00018 */
00019 /*
00020  Desc: Driver for the SICK S3000 laser
00021  Author: Robotnik Automation SLL (based on sicks3000 by Brian Gerkey, Kasper Stoy, Richard Vaughan, & Andrew Howard for Player/Stage)
00022  Date: 1 Sept 2012
00023 
00024  The sicks3000 driver controls the SICK S 3000 safety laser scanner interpreting its data output.
00025  The driver is very basic and assumes the S3000 has already been configured to continuously output
00026  its measured data on the RS422 data lines.
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 // The laser device class.
00046 class SickS3000
00047 {
00048   public:
00049 
00050     // Constructor
00051     SickS3000( std::string port, int baudrate, std::string parity, int datasize );
00052 
00053     // Destructor
00054     ~SickS3000();
00055 
00057     bool Open();
00058 
00060     bool Close();
00061 
00063     bool ReadLaser( sensor_msgs::LaserScan& scan );
00064   
00065   private:
00066 
00067     // Process range data from laser
00068     // int ProcessLaserData();
00069     int ProcessLaserData( sensor_msgs::LaserScan& scan_msg, bool& bValidData ); // public periodic function
00070 
00071     // Calculates CRC for a telegram
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     // serial port
00079     SerialDevice serial_;
00080 
00081     bool recognisedScanner;
00082 
00083     // rx buffer
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 


s3000_laser
Author(s): Roman Navarro Garcia
autogenerated on Sat Jun 8 2019 20:55:59