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 
00042 #define S3000_DEFAULT_TRANSFERRATE 500000     //
00043 #define S3000_DEFAULT_PARITY       "none"
00044 #define S3000_DEFAULT_DATA_SIZE    8
00045 
00046 // The laser device class.
00047 class SickS3000
00048 {
00049   public:
00050 
00051     // Constructor
00052     SickS3000( std::string port );
00053 
00054     // Destructor
00055     ~SickS3000();
00056 
00058     int Open();
00059 
00061     int Close();
00062 
00064     void ReadLaser( sensor_msgs::LaserScan& scan_msg, bool& bValidData ); // public periodic function
00065   
00066   private:
00067 
00068     // Process range data from laser
00069     // int ProcessLaserData();
00070     int ProcessLaserData( sensor_msgs::LaserScan& scan_msg, bool& bValidData ); // public periodic function
00071 
00072     // Calculates CRC for a telegram
00073     unsigned short CreateCRC(uint8_t *data, ssize_t len);
00074 
00075     // Get the time (in ms)
00076     int64_t GetTime();
00077 
00078     void SetScannerParams(sensor_msgs::LaserScan& scan, int data_count);
00079 
00080   protected:
00081 
00082     // serial port
00083     SerialDevice* serial;
00084 
00085     // Defines if laser is mounted inverted
00086     int mirror;
00087 
00088     // Scan width and resolution.
00089     int scan_width, scan_res;
00090 
00091     // Start and end scan angles (for restricted scan).  These are in
00092     // units of 0.01 degrees.
00093     int min_angle, max_angle;
00094 
00095     // Start and end scan segments (for restricted scan).  These are
00096     // the values used by the laser.
00097     int scan_min_segment, scan_max_segment;
00098 
00099     bool recognisedScanner;
00100 
00101     // rx buffer
00102     uint8_t * rx_buffer;
00103     unsigned int rx_buffer_size;
00104     unsigned int rx_count;
00105 
00106     // sensor_msgs::LaserScan scan;
00107 
00108   };
00109 
00110 


s3000_laser
Author(s): Román Navarro
autogenerated on Wed Sep 2 2015 11:43:29