cob_sick_s300.cpp
Go to the documentation of this file.
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/SickS300.hpp"
00072 #include <cob_sick_s300/ScannerSickS300.h>
00073 
00074 #include <boost/date_time/posix_time/posix_time.hpp>
00075 #include <boost/thread/thread.hpp>
00076 
00077 #define ROS_LOG_FOUND
00078 
00079 //####################
00080 //#### node class ####
00081 class NodeClass
00082 {
00083         //
00084         public:
00085                   
00086                 ros::NodeHandle nh;   
00087                 // topics to publish
00088                 ros::Publisher topicPub_LaserScan;
00089         ros::Publisher topicPub_Diagnostic_;
00090                 
00091                 // topics to subscribe, callback is called for new messages arriving
00092                 //--
00093                 
00094                 // service servers
00095                 //--
00096                         
00097                 // service clients
00098                 //--
00099                 
00100                 // global variables
00101                 std::string port;
00102                 int baud, scan_id, publish_frequency;
00103                 bool inverted;
00104                 double scan_duration, scan_cycle_time;
00105                 std::string frame_id;
00106                 ros::Time syncedROSTime;
00107                 unsigned int syncedSICKStamp;
00108                 bool syncedTimeReady;
00109 
00110                 // Constructor
00111                 NodeClass()
00112                 {
00113                         // create a handle for this node, initialize node
00114                         nh = ros::NodeHandle("~");
00115                         
00116                         if(!nh.hasParam("port")) ROS_WARN("Used default parameter for port");
00117                         nh.param("port", port, std::string("/dev/ttyUSB0"));
00118                         
00119                         if(!nh.hasParam("baud")) ROS_WARN("Used default parameter for baud");
00120                         nh.param("baud", baud, 500000);
00121                         
00122                         if(!nh.hasParam("scan_id")) ROS_WARN("Used default parameter for scan_id");
00123                         nh.param("scan_id", scan_id, 7);
00124                         
00125                         if(!nh.hasParam("inverted")) ROS_WARN("Used default parameter for inverted");
00126                         nh.param("inverted", inverted, false);
00127                         
00128                         if(!nh.hasParam("frame_id")) ROS_WARN("Used default parameter for frame_id");
00129                         nh.param("frame_id", frame_id, std::string("/base_laser_link"));
00130                         
00131                         if(!nh.hasParam("scan_duration")) ROS_WARN("Used default parameter for scan_duration");
00132                         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
00133                         
00134                         if(!nh.hasParam("scan_cycle_time")) ROS_WARN("Used default parameter for scan_cycle_time");
00135                         nh.param("scan_cycle_time", scan_cycle_time, 0.040); //SICK-docu says S300 scans every 40ms
00136 
00137                         if (!nh.hasParam("publish_frequency")) ROS_WARN("Used default parameter for publish_frequency");
00138                         nh.param("publish_frequency", publish_frequency, 12); //Hz
00139 
00140                         syncedSICKStamp = 0;
00141                         syncedROSTime = ros::Time::now();
00142                         syncedTimeReady = false;
00143 
00144                         // implementation of topics to publish
00145                         topicPub_LaserScan = nh.advertise<sensor_msgs::LaserScan>("scan", 1);
00146                         topicPub_Diagnostic_ = nh.advertise<diagnostic_msgs::DiagnosticArray>("/diagnostics", 1);
00147 
00148                         // implementation of topics to subscribe
00149                         //--
00150                         
00151                         // implementation of service servers
00152                         //--
00153                 }
00154                 
00155                 // Destructor
00156                 ~NodeClass() 
00157                 {
00158                 }
00159 
00160                 // topic callback functions 
00161                 // function will be called when a new message arrives on a topic
00162                 //--
00163 
00164                 // service callback functions
00165                 // function will be called when a service is querried
00166                 //--
00167                 
00168                 // other function declarations
00169                 void publishLaserScan(std::vector<double> vdDistM, std::vector<double> vdAngRAD, std::vector<double> vdIntensAU, unsigned int iSickTimeStamp, unsigned int iSickNow)
00170                 {
00171                         // fill message
00172                         int start_scan, stop_scan;
00173                         int num_readings = vdDistM.size(); // initialize with max scan size
00174                         start_scan = 0;
00175                         stop_scan = vdDistM.size();
00176                         
00177                         // Sync handling: find out exact scan time by using the syncTime-syncStamp pair:
00178                         // Timestamp: "This counter is internally incremented at each scan, i.e. every 40 ms (S300)"
00179                         if(iSickNow != 0) {
00180                                 syncedROSTime = ros::Time::now() - ros::Duration(scan_cycle_time); 
00181                                 syncedSICKStamp = iSickNow;
00182                                 syncedTimeReady = true;
00183                                 
00184                                 ROS_DEBUG("Got iSickNow, store sync-stamp: %d", syncedSICKStamp);
00185                         }
00186                         
00187                         // create LaserScan message
00188                         sensor_msgs::LaserScan laserScan;
00189                         if(syncedTimeReady) {
00190                                 double timeDiff = (int)(iSickTimeStamp - syncedSICKStamp) * scan_cycle_time;
00191                                 laserScan.header.stamp = syncedROSTime + ros::Duration(timeDiff);
00192                                 
00193                                 ROS_DEBUG("Time::now() - calculated sick time stamp = %f",(ros::Time::now() - laserScan.header.stamp).toSec());
00194                         } else {
00195                                 laserScan.header.stamp = ros::Time::now();
00196                         }
00197                         
00198                         // fill message
00199                         laserScan.header.frame_id = frame_id;
00200                         laserScan.angle_increment = vdAngRAD[start_scan + 1] - vdAngRAD[start_scan];
00201                         laserScan.range_min = 0.001;
00202                         laserScan.range_max = 30.0;
00203                         laserScan.time_increment = (scan_duration) / (vdDistM.size());
00204 
00205                         // rescale scan
00206                         num_readings = vdDistM.size();
00207                         laserScan.angle_min = vdAngRAD[start_scan]; // first ScanAngle
00208                         laserScan.angle_max = vdAngRAD[stop_scan - 1]; // last ScanAngle
00209                         laserScan.ranges.resize(num_readings);
00210                         laserScan.intensities.resize(num_readings);
00211 
00212                         
00213                         // check for inverted laser
00214                         if(inverted) {
00215                                 // to be really accurate, we now invert time_increment
00216                                 // 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.
00217                                 laserScan.time_increment = - laserScan.time_increment;
00218                         } else {
00219                                 laserScan.header.stamp = laserScan.header.stamp - ros::Duration(scan_duration); //to be consistent with the omission of the addition above
00220                         }
00221 
00222                         for(int i = 0; i < (stop_scan - start_scan); i++)
00223                         {
00224                                 if(inverted)
00225                                 {
00226                                         laserScan.ranges[i] = vdDistM[stop_scan-1-i];
00227                                         laserScan.intensities[i] = vdIntensAU[stop_scan-1-i];
00228                                 }
00229                                 else
00230                                 {
00231                                         laserScan.ranges[i] = vdDistM[start_scan + i];
00232                                         laserScan.intensities[i] = vdIntensAU[start_scan + i];
00233                                 }
00234                         }
00235         
00236                         // publish Laserscan-message
00237                         topicPub_LaserScan.publish(laserScan);
00238                         
00239                         //Diagnostics
00240                         diagnostic_msgs::DiagnosticArray diagnostics;
00241                         diagnostics.status.resize(1);
00242                         diagnostics.status[0].level = 0;
00243                         diagnostics.status[0].name = nh.getNamespace();
00244                         diagnostics.status[0].message = "sick scanner running";
00245                         topicPub_Diagnostic_.publish(diagnostics);
00246                         }
00247 
00248                                 void publishError(std::string error_str) {
00249                                         diagnostic_msgs::DiagnosticArray diagnostics;
00250                                         diagnostics.status.resize(1);
00251                                         diagnostics.status[0].level = 2;
00252                                         diagnostics.status[0].name = nh.getNamespace();
00253                                         diagnostics.status[0].message = error_str;
00254                                         topicPub_Diagnostic_.publish(diagnostics);     
00255                                 }
00256 };
00257 
00258 //#######################
00259 //#### main programm ####
00260 int main(int argc, char** argv)
00261 {
00262         // initialize ROS, spezify name of node
00263         ros::init(argc, argv, "sick_s300");
00264         
00265         NodeClass nodeClass;
00266         brics_oodl::SickS300 sickS300;
00267         brics_oodl::Errors errors;
00268 
00269         bool bOpenScan = false;
00270         
00271         unsigned int iSickTimeStamp = 0, iSickNow = 0;
00272         std::vector<double> vdDistM, vdAngRAD, vdIntensAU;
00273 
00274         brics_oodl::LaserScannerConfiguration config;
00275 
00276         config.devicePath = nodeClass.port.c_str(); // Device path of the Sick S300
00277         config.scannerID = nodeClass.scan_id;
00278 
00279         switch (nodeClass.baud) {
00280         case 9600:
00281                 config.baud = brics_oodl::BAUD_9600;
00282                 break;
00283         case 38400:
00284                 config.baud = brics_oodl::BAUD_38400;
00285                 break;
00286         case 115200:
00287                 config.baud = brics_oodl::BAUD_115200;
00288                 break;
00289                 break;
00290         case 500000:
00291                 config.baud = brics_oodl::BAUD_500K;
00292                 break;
00293         default:
00294                 config.baud = brics_oodl::BAUD_UNKNOWN;
00295                 break;
00296         }
00297 
00298         if (!sickS300.setConfiguration(config, errors)) {
00299                 errors.printErrorsToConsole();
00300         }
00301 
00302         while (!bOpenScan) {
00303         ROS_INFO("Opening scanner... (port:%s)", nodeClass.port.c_str());
00304         //bOpenScan = SickS300.open(nodeClass.port.c_str(), iBaudRate, iScanId);
00305         bOpenScan = sickS300.open(errors);
00306         // check, if it is the first try to open scanner
00307         if (!bOpenScan) {
00308                 ROS_ERROR("...scanner not available on port %s. Will retry every second.", nodeClass.port.c_str());
00309                 nodeClass.publishError("...scanner not available on port");
00310         }
00311         sleep(1); // wait for scan to get ready if successfull, or wait befor retrying
00312         }
00313         ROS_INFO("...scanner opened successfully on port %s", nodeClass.port.c_str());
00314 
00315         // main loop
00316         ros::Rate loop_rate(nodeClass.publish_frequency); // Hz
00317         while (nodeClass.nh.ok()) {
00318         // read scan
00319         ROS_DEBUG("Reading scanner...");
00320         /* Acquire the most recent scan from the Sick */
00321         if (sickS300.getData(vdDistM, vdAngRAD, vdIntensAU, iSickTimeStamp, iSickNow, errors)) {
00322                 ROS_DEBUG("...read LaserScan from scanner successfully");
00323                 // publish LaserScan
00324                 ROS_DEBUG("...publishing LaserScan message");
00325                 nodeClass.publishLaserScan(vdDistM, vdAngRAD, vdIntensAU, iSickTimeStamp, iSickNow);
00326         } else {
00327                 ROS_DEBUG("...no Scan available");
00328         }
00329         // sleep and waiting for messages, callbacks    
00330         ros::spinOnce();
00331         loop_rate.sleep();
00332         }
00333         return 0;
00334 }


cob_sick_s300
Author(s): Florian Weisshardt
autogenerated on Sun Oct 5 2014 23:05:19