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
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045
00046
00047
00048
00049
00050
00051
00052
00053
00054
00055
00056
00057
00058
00059
00060
00061 #include <ros/ros.h>
00062
00063
00064 #include <sensor_msgs/LaserScan.h>
00065
00066
00067
00068
00069
00070 #include <sick-s300/SickS300.hpp>
00071
00072 using namespace brics_oodl;
00073
00074
00075 class NodeClass
00076 {
00077
00078 public:
00079
00080 ros::NodeHandle nodeHandle;
00081
00082 ros::Publisher topicPub_LaserScan;
00083
00084
00085 std::string port;
00086 int baud, start_scan, stop_scan, scan_id;
00087 bool inverted;
00088 std::string frame_id;
00089
00090
00091
00092 NodeClass()
00093 {
00094
00095 ros::NodeHandle private_nh_("~");
00096
00097 private_nh_.param<std::string>("port", port, "/dev/ttyUSB0");
00098 private_nh_.param<int>("baud", baud, 500000);
00099 private_nh_.param<int>("scan_id", scan_id, 7);
00100 private_nh_.param<bool>("inverted", inverted, false);
00101 private_nh_.param<std::string>("frame_id", frame_id, "/base_laser_link");
00102 private_nh_.param<int>("start_scan", start_scan, 0);
00103 private_nh_.param<int>("stop_scan", stop_scan, 541);
00104
00105
00106 topicPub_LaserScan = nodeHandle.advertise<sensor_msgs::LaserScan>("scan", 1);
00107
00108
00109 }
00110
00111
00112 ~NodeClass()
00113 {
00114 }
00115
00116 void publishLaserScan(std::vector<double> vdDistM, std::vector<double> vdAngRAD, std::vector<double> vdIntensAU)
00117 {
00118
00119 int num_readings = vdDistM.size();
00120 start_scan = 0;
00121 stop_scan = vdDistM.size();
00122 double laser_frequency = 10;
00123
00124
00125 sensor_msgs::LaserScan laserScan;
00126 laserScan.header.stamp = ros::Time::now();
00127
00128
00129 laserScan.header.frame_id = frame_id;
00130 laserScan.angle_increment = vdAngRAD[start_scan + 1] - vdAngRAD[start_scan];
00131 laserScan.range_min = -135.0/180.0*3.14;
00132 laserScan.range_max = 135.0/180.0*3.14;
00133 laserScan.time_increment = (1 / laser_frequency) / (vdDistM.size());
00134
00135
00136 num_readings = stop_scan - start_scan;
00137 laserScan.angle_min = vdAngRAD[start_scan];
00138 laserScan.angle_max = vdAngRAD[stop_scan - 1];
00139 laserScan.set_ranges_size(num_readings);
00140 laserScan.set_intensities_size(num_readings);
00141
00142
00143
00144 for(int i = 0; i < (stop_scan - start_scan); i++)
00145 {
00146 if(inverted)
00147 {
00148 laserScan.ranges[i] = vdDistM[stop_scan-1-i];
00149 laserScan.intensities[i] = vdIntensAU[stop_scan-1-i];
00150 }
00151 else
00152 {
00153 laserScan.ranges[i] = vdDistM[start_scan + i];
00154 laserScan.intensities[i] = vdIntensAU[start_scan + i];
00155 }
00156 }
00157
00158
00159 topicPub_LaserScan.publish(laserScan);
00160 }
00161 };
00162
00163
00164
00165 int main(int argc, char** argv)
00166 {
00167
00168 ros::init(argc, argv, "sick_s300");
00169
00170 NodeClass nodeClass;
00171
00172
00173
00174 LaserScannerConfiguration config;
00175 config.devicePath = nodeClass.port.c_str();
00176
00177
00178 SickS300 scanner;
00179 Errors errors;
00180
00181 int iScanId = nodeClass.scan_id;
00182 bool bOpenScan = false, bRecScan = false;
00183 bool firstTry = true;
00184 std::vector<double> vdDistM, vdAngRAD, vdIntensAU;
00185
00186 while (!bOpenScan)
00187 {
00188 ROS_INFO("Opening scanner... (port:%s)",nodeClass.port.c_str());
00189 Errors errors;
00190
00191 if (!scanner.setConfiguration(config, errors)) {
00192 errors.printErrorsToConsole();
00193 return -1;
00194 }
00195
00196
00197
00198 if(!bOpenScan)
00199 {
00200 ROS_ERROR("...scanner not available on port %s. Will retry every second.",nodeClass.port.c_str());
00201 firstTry = false;
00202 }
00203 sleep(1);
00204 }
00205
00206 ROS_INFO("...scanner opened successfully on port %s",nodeClass.port.c_str());
00207
00208 ros::Rate loop_rate(5);
00209 LaserScannerData scanData;
00210 while(nodeClass.nodeHandle.ok())
00211 {
00212 ROS_DEBUG("Reading scanner...");
00213 bRecScan= scanner.getData(scanData, errors);
00214
00215 ROS_DEBUG("...read %d points from scanner successfully",vdDistM.size());
00216
00217 if(bRecScan)
00218 {
00219 ROS_DEBUG("...publishing LaserScan message");
00220
00221 }
00222 else
00223 {
00224 ROS_WARN("...no Scan available");
00225 }
00226
00227 ros::spinOnce();
00228 loop_rate.sleep();
00229 }
00230 return 0;
00231 }
00232
00233