29 #include <std_msgs/Bool.h>
30 #include <sensor_msgs/LaserScan.h>
31 #include <diagnostic_msgs/DiagnosticArray.h>
39 #include <boost/date_time/posix_time/posix_time.hpp>
40 #include <boost/thread/thread.hpp>
41 #include <boost/lexical_cast.hpp>
89 nh.
param(
"port",
port, std::string(
"/dev/ttyUSB0"));
103 if(!
nh.
hasParam(
"scan_duration"))
ROS_WARN(
"Used default parameter for scan_duration");
106 if(!
nh.
hasParam(
"scan_cycle_time"))
ROS_WARN(
"Used default parameter for scan_cycle_time");
111 if(!
nh.
hasParam(
"communication_timeout"))
ROS_WARN(
"Used default parameter for communication timeout");
123 int field_number = boost::lexical_cast<int>(field->first);
124 ROS_DEBUG(
"Found field %d in params", field_number);
126 if(!field->second.hasMember(
"scale"))
132 if(!field->second.hasMember(
"start_angle"))
134 ROS_ERROR(
"Missing parameter start_angle");
138 if(!field->second.hasMember(
"stop_angle"))
140 ROS_ERROR(
"Missing parameter stop_angle");
145 param.dScale = field->second[
"scale"];
146 param.dStartAngle = field->second[
"start_angle"];
147 param.dStopAngle = field->second[
"stop_angle"];
160 param.dStartAngle = -135.0/180.0*M_PI;
161 param.dStopAngle = 135.0/180.0*M_PI;
167 ROS_ERROR(
"Node is going to shut down.");
188 std::vector< double > ranges, rangeAngles, intensities;
189 unsigned int iSickTimeStamp, iSickNow;
192 static boost::posix_time::ptime point_time_communication_ok = boost::posix_time::microsec_clock::local_time();
205 publishLaserScan(ranges, rangeAngles, intensities, iSickTimeStamp, iSickNow);
208 point_time_communication_ok = boost::posix_time::microsec_clock::local_time();
212 boost::posix_time::time_duration diff = boost::posix_time::microsec_clock::local_time() - point_time_communication_ok;
231 this->inStandby_.data = inStandby;
236 void publishLaserScan(std::vector<double> vdDistM, std::vector<double> vdAngRAD, std::vector<double> vdIntensAU,
unsigned int iSickTimeStamp,
unsigned int iSickNow)
239 int start_scan, stop_scan;
240 int num_readings = vdDistM.size();
242 stop_scan = vdDistM.size();
255 sensor_msgs::LaserScan laserScan;
260 ROS_DEBUG(
"Time::now() - calculated sick time stamp = %f",(
ros::Time::now() - laserScan.header.stamp).toSec());
266 laserScan.header.frame_id =
frame_id;
267 laserScan.angle_increment = vdAngRAD[start_scan + 1] - vdAngRAD[start_scan];
268 laserScan.range_min = 0.001;
269 laserScan.range_max = 29.5;
270 laserScan.time_increment = (
scan_duration) / (vdDistM.size());
273 num_readings = vdDistM.size();
274 laserScan.angle_min = vdAngRAD[start_scan];
275 laserScan.angle_max = vdAngRAD[stop_scan - 1];
276 laserScan.ranges.resize(num_readings);
277 laserScan.intensities.resize(num_readings);
284 laserScan.time_increment = - laserScan.time_increment;
289 for(
int i = 0; i < (stop_scan - start_scan); i++)
293 laserScan.ranges[i] = vdDistM[stop_scan-1-i];
294 laserScan.intensities[i] = vdIntensAU[stop_scan-1-i];
298 laserScan.ranges[i] = vdDistM[start_scan + i];
299 laserScan.intensities[i] = vdIntensAU[start_scan + i];
307 diagnostic_msgs::DiagnosticArray diagnostics;
309 diagnostics.status.resize(1);
310 diagnostics.status[0].level = 0;
312 diagnostics.status[0].message =
"sick scanner running";
317 diagnostic_msgs::DiagnosticArray diagnostics;
319 diagnostics.status.resize(1);
320 diagnostics.status[0].level = 2;
322 diagnostics.status[0].message = error_str;
327 diagnostic_msgs::DiagnosticArray diagnostics;
329 diagnostics.status.resize(1);
330 diagnostics.status[0].level = 1;
332 diagnostics.status[0].message = warn_str;
339 int main(
int argc,
char** argv)
348 bool bOpenScan =
false;
349 while (!bOpenScan &&
ros::ok()) {
350 ROS_INFO(
"Opening scanner... (port:%s)", nodeClass.
port.c_str());
352 bOpenScan = nodeClass.
open();
356 ROS_ERROR(
"...scanner not available on port %s. Will retry every second.", nodeClass.
port.c_str());
357 nodeClass.
publishError(
"...scanner not available on port");
361 ROS_INFO(
"...scanner opened successfully on port %s", nodeClass.
port.c_str());