00001 /* 00002 * 00003 * sicks300.h 00004 * 00005 * 00006 * Copyright (C) 2010 00007 * Autonomous Intelligent Systems Group 00008 * University of Bonn, Germany 00009 * 00010 * 00011 * Authors: Andreas Hochrath, Torsten Fiolka 00012 * 00013 * 00014 * This program is free software; you can redistribute it and/or modify 00015 * it under the terms of the GNU General Public License as published by 00016 * the Free Software Foundation; either version 3 of the License, or 00017 * (at your option) any later version. 00018 * 00019 * This program is distributed in the hope that it will be useful, 00020 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00021 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00022 * GNU General Public License for more details. 00023 * 00024 * You should have received a copy of the GNU General Public License 00025 * along with this program; if not, write to the Free Software 00026 * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA 00027 * 00028 * 00029 * Origin: 00030 * Player - One Hell of a Robot Server 00031 * serialstream.cc & sicks3000.cc 00032 * Copyright (C) 2003 00033 * Brian Gerkey 00034 * Copyright (C) 2000 00035 * Brian Gerkey, Kasper Stoy, Richard Vaughan, & Andrew Howard 00036 * 00037 */ 00038 00039 #ifndef __SICKS300_H__ 00040 #define __SICKS300_H__ 00041 00042 #include "serialcomm_s300.h" 00043 00044 #include <string> 00045 00046 #include <ros/ros.h> 00047 #include <sensor_msgs/LaserScan.h> 00048 #include <tf/transform_broadcaster.h> 00049 00057 class SickS300 00058 { 00059 public: 00060 00061 SickS300(); 00062 ~SickS300(); 00063 00065 void update(); 00066 00068 void broadcast_transform(); 00069 00070 protected: 00071 00073 SerialCommS300 serial_comm_; 00074 00075 sensor_msgs::LaserScan scan_data_; 00076 ros::Publisher scan_data_publisher_; 00077 00078 tf::TransformBroadcaster tf_broadcaster_; 00079 tf::Vector3 transform_vector_; 00080 00082 bool reduced_FOV_; 00083 00085 bool send_transform_; 00086 00087 std::string device_name_; 00088 int baud_rate_; 00089 int connected_; 00090 }; 00091 00092 #endif // __SICKS300_H__