$search
00001 /**************************************************************** 00002 * 00003 * Copyright (c) 2010 00004 * 00005 * Fraunhofer Institute for Manufacturing Engineering 00006 * and Automation (IPA) 00007 * 00008 * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ 00009 * 00010 * Project name: care-o-bot 00011 * ROS stack name: cob_driver 00012 * ROS package name: cob_sick_s300 00013 * Description: 00014 * 00015 * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ 00016 * 00017 * Author: Florian Weisshardt, email:florian.weisshardt@ipa.fhg.de 00018 * Supervised by: Christian Connette, email:christian.connette@ipa.fhg.de 00019 * 00020 * Date of creation: Jan 2010 00021 * ToDo: 00022 * 00023 * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ 00024 * 00025 * Redistribution and use in source and binary forms, with or without 00026 * modification, are permitted provided that the following conditions are met: 00027 * 00028 * * Redistributions of source code must retain the above copyright 00029 * notice, this list of conditions and the following disclaimer. 00030 * * Redistributions in binary form must reproduce the above copyright 00031 * notice, this list of conditions and the following disclaimer in the 00032 * documentation and/or other materials provided with the distribution. 00033 * * Neither the name of the Fraunhofer Institute for Manufacturing 00034 * Engineering and Automation (IPA) nor the names of its 00035 * contributors may be used to endorse or promote products derived from 00036 * this software without specific prior written permission. 00037 * 00038 * This program is free software: you can redistribute it and/or modify 00039 * it under the terms of the GNU Lesser General Public License LGPL as 00040 * published by the Free Software Foundation, either version 3 of the 00041 * License, or (at your option) any later version. 00042 * 00043 * This program is distributed in the hope that it will be useful, 00044 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00045 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00046 * GNU Lesser General Public License LGPL for more details. 00047 * 00048 * You should have received a copy of the GNU Lesser General Public 00049 * License LGPL along with this program. 00050 * If not, see <http://www.gnu.org/licenses/>. 00051 * 00052 ****************************************************************/ 00053 00054 //################## 00055 //#### includes #### 00056 00057 // standard includes 00058 //-- 00059 00060 // ROS includes 00061 #include <ros/ros.h> 00062 00063 // ROS message includes 00064 #include <sensor_msgs/LaserScan.h> 00065 #include <diagnostic_msgs/DiagnosticArray.h> 00066 00067 // ROS service includes 00068 //-- 00069 00070 // external includes 00071 #include <cob_sick_s300/ScannerSickS300.h> 00072 00073 //#################### 00074 //#### node class #### 00075 class NodeClass 00076 { 00077 // 00078 public: 00079 00080 ros::NodeHandle nh; 00081 // topics to publish 00082 ros::Publisher topicPub_LaserScan; 00083 ros::Publisher topicPub_Diagnostic_; 00084 00085 // topics to subscribe, callback is called for new messages arriving 00086 //-- 00087 00088 // service servers 00089 //-- 00090 00091 // service clients 00092 //-- 00093 00094 // global variables 00095 std::string port; 00096 int baud, scan_id; 00097 bool inverted; 00098 double scan_duration, scan_cycle_time; 00099 std::string frame_id; 00100 ros::Time syncedROSTime; 00101 unsigned int syncedSICKStamp; 00102 bool syncedTimeReady; 00103 00104 // Constructor 00105 NodeClass() 00106 { 00107 // create a handle for this node, initialize node 00108 nh = ros::NodeHandle("~"); 00109 00110 if(!nh.hasParam("port")) ROS_WARN("Used default parameter for port"); 00111 nh.param("port", port, std::string("/dev/ttyUSB0")); 00112 00113 if(!nh.hasParam("baud")) ROS_WARN("Used default parameter for baud"); 00114 nh.param("baud", baud, 500000); 00115 00116 if(!nh.hasParam("scan_id")) ROS_WARN("Used default parameter for scan_id"); 00117 nh.param("scan_id", scan_id, 7); 00118 00119 if(!nh.hasParam("inverted")) ROS_WARN("Used default parameter for inverted"); 00120 nh.param("inverted", inverted, false); 00121 00122 if(!nh.hasParam("frame_id")) ROS_WARN("Used default parameter for frame_id"); 00123 nh.param("frame_id", frame_id, std::string("/base_laser_link")); 00124 00125 if(!nh.hasParam("scan_duration")) ROS_WARN("Used default parameter for scan_duration"); 00126 nh.param("scan_duration", scan_duration, 0.025); //no info about that in SICK-docu, but 0.025 is believable and looks good in rviz 00127 00128 if(!nh.hasParam("scan_cycle_time")) ROS_WARN("Used default parameter for scan_cycle_time"); 00129 nh.param("scan_cycle_time", scan_cycle_time, 0.040); //SICK-docu says S300 scans every 40ms 00130 00131 syncedSICKStamp = 0; 00132 syncedROSTime = ros::Time::now(); 00133 syncedTimeReady = false; 00134 00135 // implementation of topics to publish 00136 topicPub_LaserScan = nh.advertise<sensor_msgs::LaserScan>("scan", 1); 00137 topicPub_Diagnostic_ = nh.advertise<diagnostic_msgs::DiagnosticArray>("/diagnostics", 1); 00138 00139 // implementation of topics to subscribe 00140 //-- 00141 00142 // implementation of service servers 00143 //-- 00144 } 00145 00146 // Destructor 00147 ~NodeClass() 00148 { 00149 } 00150 00151 // topic callback functions 00152 // function will be called when a new message arrives on a topic 00153 //-- 00154 00155 // service callback functions 00156 // function will be called when a service is querried 00157 //-- 00158 00159 // other function declarations 00160 void publishLaserScan(std::vector<double> vdDistM, std::vector<double> vdAngRAD, std::vector<double> vdIntensAU, unsigned int iSickTimeStamp, unsigned int iSickNow) 00161 { 00162 // fill message 00163 int start_scan, stop_scan; 00164 int num_readings = vdDistM.size(); // initialize with max scan size 00165 start_scan = 0; 00166 stop_scan = vdDistM.size(); 00167 00168 // Sync handling: find out exact scan time by using the syncTime-syncStamp pair: 00169 // Timestamp: "This counter is internally incremented at each scan, i.e. every 40 ms (S300)" 00170 if(iSickNow != 0) { 00171 syncedROSTime = ros::Time::now() - ros::Duration(scan_cycle_time); 00172 syncedSICKStamp = iSickNow; 00173 syncedTimeReady = true; 00174 00175 ROS_DEBUG("Got iSickNow, store sync-stamp: %d", syncedSICKStamp); 00176 } 00177 00178 // create LaserScan message 00179 sensor_msgs::LaserScan laserScan; 00180 if(syncedTimeReady) { 00181 double timeDiff = (int)(iSickTimeStamp - syncedSICKStamp) * scan_cycle_time; 00182 laserScan.header.stamp = syncedROSTime + ros::Duration(timeDiff); 00183 00184 ROS_DEBUG("Time::now() - calculated sick time stamp = %f",(ros::Time::now() - laserScan.header.stamp).toSec()); 00185 } else { 00186 laserScan.header.stamp = ros::Time::now(); 00187 } 00188 00189 // fill message 00190 laserScan.header.frame_id = frame_id; 00191 laserScan.angle_increment = vdAngRAD[start_scan + 1] - vdAngRAD[start_scan]; 00192 laserScan.range_min = 0.001; 00193 laserScan.range_max = 30.0; 00194 laserScan.time_increment = (scan_duration) / (vdDistM.size()); 00195 00196 // rescale scan 00197 num_readings = vdDistM.size(); 00198 laserScan.angle_min = vdAngRAD[start_scan]; // first ScanAngle 00199 laserScan.angle_max = vdAngRAD[stop_scan - 1]; // last ScanAngle 00200 laserScan.ranges.resize(num_readings); 00201 laserScan.intensities.resize(num_readings); 00202 00203 00204 // check for inverted laser 00205 if(inverted) { 00206 // to be really accurate, we now invert time_increment 00207 // laserScan.header.stamp = laserScan.header.stamp + ros::Duration(scan_duration); //adding of the sum over all negative increments would be mathematically correct, but looks worse. 00208 laserScan.time_increment = - laserScan.time_increment; 00209 } else { 00210 laserScan.header.stamp = laserScan.header.stamp - ros::Duration(scan_duration); //to be consistent with the omission of the addition above 00211 } 00212 00213 for(int i = 0; i < (stop_scan - start_scan); i++) 00214 { 00215 if(inverted) 00216 { 00217 laserScan.ranges[i] = vdDistM[stop_scan-1-i]; 00218 laserScan.intensities[i] = vdIntensAU[stop_scan-1-i]; 00219 } 00220 else 00221 { 00222 laserScan.ranges[i] = vdDistM[start_scan + i]; 00223 laserScan.intensities[i] = vdIntensAU[start_scan + i]; 00224 } 00225 } 00226 00227 // publish Laserscan-message 00228 topicPub_LaserScan.publish(laserScan); 00229 00230 //Diagnostics 00231 diagnostic_msgs::DiagnosticArray diagnostics; 00232 diagnostics.status.resize(1); 00233 diagnostics.status[0].level = 0; 00234 diagnostics.status[0].name = nh.getNamespace(); 00235 diagnostics.status[0].message = "sick scanner running"; 00236 topicPub_Diagnostic_.publish(diagnostics); 00237 } 00238 00239 void publishError(std::string error_str) { 00240 diagnostic_msgs::DiagnosticArray diagnostics; 00241 diagnostics.status.resize(1); 00242 diagnostics.status[0].level = 2; 00243 diagnostics.status[0].name = nh.getNamespace(); 00244 diagnostics.status[0].message = error_str; 00245 topicPub_Diagnostic_.publish(diagnostics); 00246 } 00247 }; 00248 00249 //####################### 00250 //#### main programm #### 00251 int main(int argc, char** argv) 00252 { 00253 // initialize ROS, spezify name of node 00254 ros::init(argc, argv, "sick_s300"); 00255 00256 NodeClass nodeClass; 00257 ScannerSickS300 SickS300; 00258 00259 int iBaudRate = nodeClass.baud; 00260 int iScanId = nodeClass.scan_id; 00261 bool bOpenScan = false, bRecScan = false; 00262 bool firstTry = true; 00263 00264 unsigned int iSickTimeStamp, iSickNow; 00265 std::vector<double> vdDistM, vdAngRAD, vdIntensAU; 00266 00267 while (!bOpenScan) 00268 { 00269 ROS_INFO("Opening scanner... (port:%s)",nodeClass.port.c_str()); 00270 bOpenScan = SickS300.open(nodeClass.port.c_str(), iBaudRate, iScanId); 00271 00272 // check, if it is the first try to open scanner 00273 if(!bOpenScan) 00274 { 00275 ROS_ERROR("...scanner not available on port %s. Will retry every second.",nodeClass.port.c_str()); 00276 nodeClass.publishError("...scanner not available on port"); 00277 firstTry = false; 00278 } 00279 sleep(1); // wait for scan to get ready if successfull, or wait befor retrying 00280 } 00281 ROS_INFO("...scanner opened successfully on port %s",nodeClass.port.c_str()); 00282 00283 // main loop 00284 ros::Rate loop_rate(5); // Hz 00285 while(nodeClass.nh.ok()) 00286 { 00287 // read scan 00288 ROS_DEBUG("Reading scanner..."); 00289 bRecScan = SickS300.getScan(vdDistM, vdAngRAD, vdIntensAU, iSickTimeStamp, iSickNow); 00290 ROS_DEBUG("...read %d points from scanner successfully",(int)vdDistM.size()); 00291 // publish LaserScan 00292 if(bRecScan) 00293 { 00294 ROS_DEBUG("...publishing LaserScan message"); 00295 nodeClass.publishLaserScan(vdDistM, vdAngRAD, vdIntensAU, iSickTimeStamp, iSickNow); 00296 } 00297 else 00298 { 00299 ROS_WARN("...no Scan available"); 00300 } 00301 00302 // sleep and waiting for messages, callbacks 00303 ros::spinOnce(); 00304 loop_rate.sleep(); 00305 } 00306 return 0; 00307 }