00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025 #include <ros/ros.h>
00026 #include <XmlRpcException.h>
00027
00028
00029 #include <std_msgs/Bool.h>
00030 #include <sensor_msgs/LaserScan.h>
00031 #include <diagnostic_msgs/DiagnosticArray.h>
00032
00033
00034
00035
00036
00037 #include <cob_sick_s300/ScannerSickS300.h>
00038
00039 #include <boost/date_time/posix_time/posix_time.hpp>
00040 #include <boost/thread/thread.hpp>
00041 #include <boost/lexical_cast.hpp>
00042
00043 #define ROS_LOG_FOUND
00044
00045
00046
00047 class NodeClass
00048 {
00049
00050 public:
00051
00052 ros::NodeHandle nh;
00053
00054 ros::Publisher topicPub_LaserScan;
00055 ros::Publisher topicPub_InStandby;
00056 ros::Publisher topicPub_Diagnostic_;
00057
00058
00059
00060
00061
00062
00063
00064
00065
00066
00067
00068 std::string port;
00069 std::string node_name;
00070 int baud, scan_id;
00071 bool inverted;
00072 double scan_duration, scan_cycle_time;
00073 std::string frame_id;
00074 ros::Time syncedROSTime;
00075 unsigned int syncedSICKStamp;
00076 bool syncedTimeReady;
00077 bool debug_;
00078 double communication_timeout;
00079 ScannerSickS300 scanner_;
00080 std_msgs::Bool inStandby_;
00081
00082
00083 NodeClass()
00084 {
00085
00086
00087
00088 if(!nh.hasParam("port")) ROS_WARN("Used default parameter for port");
00089 nh.param("port", port, std::string("/dev/ttyUSB0"));
00090
00091 if(!nh.hasParam("baud")) ROS_WARN("Used default parameter for baud");
00092 nh.param("baud", baud, 500000);
00093
00094 if(!nh.hasParam("scan_id")) ROS_WARN("Used default parameter for scan_id");
00095 nh.param("scan_id", scan_id, 7);
00096
00097 if(!nh.hasParam("inverted")) ROS_WARN("Used default parameter for inverted");
00098 nh.param("inverted", inverted, false);
00099
00100 if(!nh.hasParam("frame_id")) ROS_WARN("Used default parameter for frame_id");
00101 nh.param("frame_id", frame_id, std::string("/base_laser_link"));
00102
00103 if(!nh.hasParam("scan_duration")) ROS_WARN("Used default parameter for scan_duration");
00104 nh.param("scan_duration", scan_duration, 0.025);
00105
00106 if(!nh.hasParam("scan_cycle_time")) ROS_WARN("Used default parameter for scan_cycle_time");
00107 nh.param("scan_cycle_time", scan_cycle_time, 0.040);
00108
00109 if(nh.hasParam("debug")) nh.param("debug", debug_, false);
00110
00111 if(!nh.hasParam("communication_timeout")) ROS_WARN("Used default parameter for communication timeout");
00112 nh.param("communication_timeout", communication_timeout, 0.2);
00113
00114 try
00115 {
00116
00117 XmlRpc::XmlRpcValue field_params;
00118 if(nh.getParam("fields",field_params) && field_params.getType() == XmlRpc::XmlRpcValue::TypeStruct)
00119 {
00120 for(XmlRpc::XmlRpcValue::iterator field=field_params.begin(); field!=field_params.
00121 end(); field++)
00122 {
00123 int field_number = boost::lexical_cast<int>(field->first);
00124 ROS_DEBUG("Found field %d in params", field_number);
00125
00126 if(!field->second.hasMember("scale"))
00127 {
00128 ROS_ERROR("Missing parameter scale");
00129 continue;
00130 }
00131
00132 if(!field->second.hasMember("start_angle"))
00133 {
00134 ROS_ERROR("Missing parameter start_angle");
00135 continue;
00136 }
00137
00138 if(!field->second.hasMember("stop_angle"))
00139 {
00140 ROS_ERROR("Missing parameter stop_angle");
00141 continue;
00142 }
00143
00144 ScannerSickS300::ParamType param;
00145 param.dScale = field->second["scale"];
00146 param.dStartAngle = field->second["start_angle"];
00147 param.dStopAngle = field->second["stop_angle"];
00148 scanner_.setRangeField(field_number, param);
00149
00150 ROS_DEBUG("params %f %f %f", param.dScale, param.dStartAngle, param.dStopAngle);
00151 }
00152 }
00153 else
00154 {
00155
00156
00157
00158 ScannerSickS300::ParamType param;
00159 param.dScale = 0.01;
00160 param.dStartAngle = -135.0/180.0*M_PI;
00161 param.dStopAngle = 135.0/180.0*M_PI;
00162 scanner_.setRangeField(1, param);
00163 }
00164 } catch(XmlRpc::XmlRpcException e)
00165 {
00166 ROS_ERROR_STREAM("Not all params for the Sick S300 fieldset could be read: " << e.getMessage() << "! Error code: " << e.getCode());
00167 ROS_ERROR("Node is going to shut down.");
00168 exit(-1);
00169 }
00170
00171 syncedSICKStamp = 0;
00172 syncedROSTime = ros::Time::now();
00173 syncedTimeReady = false;
00174
00175 node_name = ros::this_node::getName();
00176
00177
00178 topicPub_LaserScan = nh.advertise<sensor_msgs::LaserScan>("scan", 1);
00179 topicPub_InStandby = nh.advertise<std_msgs::Bool>("scan_standby", 1);
00180 topicPub_Diagnostic_ = nh.advertise<diagnostic_msgs::DiagnosticArray>("/diagnostics", 1);
00181 }
00182
00183 bool open() {
00184 return scanner_.open(port.c_str(), baud, scan_id);
00185 }
00186
00187 bool receiveScan() {
00188 std::vector< double > ranges, rangeAngles, intensities;
00189 unsigned int iSickTimeStamp, iSickNow;
00190
00191 int result = scanner_.getScan(ranges, rangeAngles, intensities, iSickTimeStamp, iSickNow, debug_);
00192 static boost::posix_time::ptime point_time_communiaction_ok = boost::posix_time::microsec_clock::local_time();
00193
00194 if(result)
00195 {
00196 if(scanner_.isInStandby())
00197 {
00198 publishWarn("scanner in standby");
00199 ROS_WARN_THROTTLE(30, "scanner %s on port %s in standby", node_name.c_str(), port.c_str());
00200 publishStandby(true);
00201 }
00202 else
00203 {
00204 publishStandby(false);
00205 publishLaserScan(ranges, rangeAngles, intensities, iSickTimeStamp, iSickNow);
00206 }
00207
00208 point_time_communiaction_ok = boost::posix_time::microsec_clock::local_time();
00209 }
00210 else
00211 {
00212 boost::posix_time::time_duration diff = boost::posix_time::microsec_clock::local_time() - point_time_communiaction_ok;
00213
00214 if (diff.total_milliseconds() > static_cast<int>(1000*communication_timeout))
00215 {
00216 ROS_WARN("Communiaction timeout");
00217 return false;
00218 }
00219 }
00220
00221 return true;
00222 }
00223
00224
00225 ~NodeClass()
00226 {
00227 }
00228
00229 void publishStandby(bool inStandby)
00230 {
00231 this->inStandby_.data = inStandby;
00232 topicPub_InStandby.publish(this->inStandby_);
00233 }
00234
00235
00236 void publishLaserScan(std::vector<double> vdDistM, std::vector<double> vdAngRAD, std::vector<double> vdIntensAU, unsigned int iSickTimeStamp, unsigned int iSickNow)
00237 {
00238
00239 int start_scan, stop_scan;
00240 int num_readings = vdDistM.size();
00241 start_scan = 0;
00242 stop_scan = vdDistM.size();
00243
00244
00245
00246 if(iSickNow != 0) {
00247 syncedROSTime = ros::Time::now() - ros::Duration(scan_cycle_time);
00248 syncedSICKStamp = iSickNow;
00249 syncedTimeReady = true;
00250
00251 ROS_DEBUG("Got iSickNow, store sync-stamp: %d", syncedSICKStamp);
00252 } else syncedTimeReady = false;
00253
00254
00255 sensor_msgs::LaserScan laserScan;
00256 if(syncedTimeReady) {
00257 double timeDiff = (int)(iSickTimeStamp - syncedSICKStamp) * scan_cycle_time;
00258 laserScan.header.stamp = syncedROSTime + ros::Duration(timeDiff);
00259
00260 ROS_DEBUG("Time::now() - calculated sick time stamp = %f",(ros::Time::now() - laserScan.header.stamp).toSec());
00261 } else {
00262 laserScan.header.stamp = ros::Time::now();
00263 }
00264
00265
00266 laserScan.header.frame_id = frame_id;
00267 laserScan.angle_increment = vdAngRAD[start_scan + 1] - vdAngRAD[start_scan];
00268 laserScan.range_min = 0.001;
00269 laserScan.range_max = 29.5;
00270 laserScan.time_increment = (scan_duration) / (vdDistM.size());
00271
00272
00273 num_readings = vdDistM.size();
00274 laserScan.angle_min = vdAngRAD[start_scan];
00275 laserScan.angle_max = vdAngRAD[stop_scan - 1];
00276 laserScan.ranges.resize(num_readings);
00277 laserScan.intensities.resize(num_readings);
00278
00279
00280
00281 if(inverted) {
00282
00283
00284 laserScan.time_increment = - laserScan.time_increment;
00285 } else {
00286 laserScan.header.stamp = laserScan.header.stamp - ros::Duration(scan_duration);
00287 }
00288
00289 for(int i = 0; i < (stop_scan - start_scan); i++)
00290 {
00291 if(inverted)
00292 {
00293 laserScan.ranges[i] = vdDistM[stop_scan-1-i];
00294 laserScan.intensities[i] = vdIntensAU[stop_scan-1-i];
00295 }
00296 else
00297 {
00298 laserScan.ranges[i] = vdDistM[start_scan + i];
00299 laserScan.intensities[i] = vdIntensAU[start_scan + i];
00300 }
00301 }
00302
00303
00304 topicPub_LaserScan.publish(laserScan);
00305
00306
00307 diagnostic_msgs::DiagnosticArray diagnostics;
00308 diagnostics.header.stamp = ros::Time::now();
00309 diagnostics.status.resize(1);
00310 diagnostics.status[0].level = 0;
00311 diagnostics.status[0].name = nh.getNamespace();
00312 diagnostics.status[0].message = "sick scanner running";
00313 topicPub_Diagnostic_.publish(diagnostics);
00314 }
00315
00316 void publishError(std::string error_str) {
00317 diagnostic_msgs::DiagnosticArray diagnostics;
00318 diagnostics.header.stamp = ros::Time::now();
00319 diagnostics.status.resize(1);
00320 diagnostics.status[0].level = 2;
00321 diagnostics.status[0].name = nh.getNamespace();
00322 diagnostics.status[0].message = error_str;
00323 topicPub_Diagnostic_.publish(diagnostics);
00324 }
00325
00326 void publishWarn(std::string warn_str) {
00327 diagnostic_msgs::DiagnosticArray diagnostics;
00328 diagnostics.header.stamp = ros::Time::now();
00329 diagnostics.status.resize(1);
00330 diagnostics.status[0].level = 1;
00331 diagnostics.status[0].name = nh.getNamespace();
00332 diagnostics.status[0].message = warn_str;
00333 topicPub_Diagnostic_.publish(diagnostics);
00334 }
00335 };
00336
00337
00338
00339 int main(int argc, char** argv)
00340 {
00341
00342 ros::init(argc, argv, "sick_s300");
00343
00344 NodeClass nodeClass;
00345
00346 while (ros::ok())
00347 {
00348 bool bOpenScan = false;
00349 while (!bOpenScan && ros::ok()) {
00350 ROS_INFO("Opening scanner... (port:%s)", nodeClass.port.c_str());
00351
00352 bOpenScan = nodeClass.open();
00353
00354
00355 if (!bOpenScan) {
00356 ROS_ERROR("...scanner not available on port %s. Will retry every second.", nodeClass.port.c_str());
00357 nodeClass.publishError("...scanner not available on port");
00358 }
00359 sleep(1);
00360 }
00361 ROS_INFO("...scanner opened successfully on port %s", nodeClass.port.c_str());
00362
00363
00364 while (ros::ok()) {
00365
00366 if (!nodeClass.receiveScan())
00367 {
00368 break;
00369 }
00370 ros::spinOnce();
00371 }
00372 }
00373 return 0;
00374 }