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 #include "ros/ros.h"
00040 #include "sensor_msgs/LaserScan.h"
00041 #include "std_srvs/Empty.h"
00042
00043 #include "rplidar.h"
00044
00045 #ifndef _countof
00046 #define _countof(_Array) (int)(sizeof(_Array) / sizeof(_Array[0]))
00047 #endif
00048
00049 #define DEG2RAD(x) ((x)*M_PI/180.)
00050
00051 using namespace rp::standalone::rplidar;
00052
00053 RPlidarDriver * drv = NULL;
00054
00055 void publish_scan(ros::Publisher *pub,
00056 rplidar_response_measurement_node_t *nodes,
00057 size_t node_count, ros::Time start,
00058 double scan_time, bool inverted,
00059 float angle_min, float angle_max,
00060 std::string frame_id)
00061 {
00062 static int scan_count = 0;
00063 sensor_msgs::LaserScan scan_msg;
00064
00065 scan_msg.header.stamp = start;
00066 scan_msg.header.frame_id = frame_id;
00067 scan_count++;
00068
00069 scan_msg.angle_min = M_PI - angle_min;
00070 scan_msg.angle_max = M_PI - angle_max;
00071 scan_msg.angle_increment =
00072 (scan_msg.angle_max - scan_msg.angle_min) / (double)(node_count-1);
00073
00074 scan_msg.scan_time = scan_time;
00075 scan_msg.time_increment = scan_time / (double)(node_count-1);
00076
00077 scan_msg.range_min = 0.15;
00078 scan_msg.range_max = 6.;
00079
00080 scan_msg.intensities.resize(node_count);
00081 scan_msg.ranges.resize(node_count);
00082 if (!inverted) {
00083 for (size_t i = 0; i < node_count; i++) {
00084 float read_value = (float) nodes[i].distance_q2/4.0f/1000;
00085 if (read_value == 0.0)
00086 scan_msg.ranges[i] = std::numeric_limits<float>::infinity();
00087 else
00088 scan_msg.ranges[i] = read_value;
00089 scan_msg.intensities[i] = (float) (nodes[i].sync_quality >> 2);
00090 }
00091 } else {
00092 for (size_t i = 0; i < node_count; i++) {
00093 float read_value = (float)nodes[i].distance_q2/4.0f/1000;
00094 if (read_value == 0.0)
00095 scan_msg.ranges[node_count-1-i] = std::numeric_limits<float>::infinity();
00096 else
00097 scan_msg.ranges[node_count-1-i] = read_value;
00098 scan_msg.intensities[node_count-1-i] = (float) (nodes[i].sync_quality >> 2);
00099 }
00100 }
00101
00102 pub->publish(scan_msg);
00103 }
00104
00105 bool checkRPLIDARHealth(RPlidarDriver * drv)
00106 {
00107 u_result op_result;
00108 rplidar_response_device_health_t healthinfo;
00109
00110 op_result = drv->getHealth(healthinfo);
00111 if (IS_OK(op_result)) {
00112 printf("RPLidar health status : %d\n", healthinfo.status);
00113
00114 if (healthinfo.status == RPLIDAR_STATUS_ERROR) {
00115 fprintf(stderr, "Error, rplidar internal error detected."
00116 "Please reboot the device to retry.\n");
00117 return false;
00118 } else {
00119 return true;
00120 }
00121
00122 } else {
00123 fprintf(stderr, "Error, cannot retrieve rplidar health code: %x\n",
00124 op_result);
00125 return false;
00126 }
00127 }
00128
00129 bool stop_motor(std_srvs::Empty::Request &req,
00130 std_srvs::Empty::Response &res)
00131 {
00132 if(!drv)
00133 return false;
00134
00135 ROS_DEBUG("Stop motor");
00136 drv->stop();
00137 drv->stopMotor();
00138 return true;
00139 }
00140
00141 bool start_motor(std_srvs::Empty::Request &req,
00142 std_srvs::Empty::Response &res)
00143 {
00144 if(!drv)
00145 return false;
00146 ROS_DEBUG("Start motor");
00147 drv->startMotor();
00148 drv->startScan();;
00149 return true;
00150 }
00151
00152
00153 int main(int argc, char * argv[]) {
00154 ros::init(argc, argv, "rplidar_node");
00155
00156 std::string serial_port;
00157 int serial_baudrate = 115200;
00158 std::string frame_id;
00159 bool inverted = false;
00160 bool angle_compensate = true;
00161
00162 ros::NodeHandle nh;
00163 ros::Publisher scan_pub = nh.advertise<sensor_msgs::LaserScan>("scan", 1000);
00164 ros::NodeHandle nh_private("~");
00165 nh_private.param<std::string>("serial_port", serial_port, "/dev/ttyUSB0");
00166 nh_private.param<int>("serial_baudrate", serial_baudrate, 115200);
00167 nh_private.param<std::string>("frame_id", frame_id, "laser_frame");
00168 nh_private.param<bool>("inverted", inverted, "false");
00169 nh_private.param<bool>("angle_compensate", angle_compensate, "true");
00170
00171 u_result op_result;
00172
00173
00174 drv = RPlidarDriver::CreateDriver(RPlidarDriver::DRIVER_TYPE_SERIALPORT);
00175
00176 if (!drv) {
00177 fprintf(stderr, "Create Driver fail, exit\n");
00178 return -2;
00179 }
00180
00181
00182 if (IS_FAIL(drv->connect(serial_port.c_str(), (_u32)serial_baudrate))) {
00183 fprintf(stderr, "Error, cannot bind to the specified serial port %s.\n"
00184 , serial_port.c_str());
00185 RPlidarDriver::DisposeDriver(drv);
00186 return -1;
00187 }
00188
00189
00190 if (!checkRPLIDARHealth(drv)) {
00191 RPlidarDriver::DisposeDriver(drv);
00192 return -1;
00193 }
00194
00195
00196 ros::ServiceServer stop_motor_service = nh.advertiseService("stop_motor", stop_motor);
00197 ros::ServiceServer start_motor_service = nh.advertiseService("start_motor", start_motor);
00198
00199
00200 drv->startScan();
00201
00202 ros::Time start_scan_time;
00203 ros::Time end_scan_time;
00204 double scan_duration;
00205 while (ros::ok()) {
00206
00207 rplidar_response_measurement_node_t nodes[360*2];
00208 size_t count = _countof(nodes);
00209
00210 start_scan_time = ros::Time::now();
00211 op_result = drv->grabScanData(nodes, count);
00212 end_scan_time = ros::Time::now();
00213 scan_duration = (end_scan_time - start_scan_time).toSec() * 1e-3;
00214
00215 if (op_result == RESULT_OK) {
00216 op_result = drv->ascendScanData(nodes, count);
00217
00218 float angle_min = DEG2RAD(0.0f);
00219 float angle_max = DEG2RAD(359.0f);
00220 if (op_result == RESULT_OK) {
00221 if (angle_compensate) {
00222 const int angle_compensate_nodes_count = 360;
00223 const int angle_compensate_multiple = 1;
00224 int angle_compensate_offset = 0;
00225 rplidar_response_measurement_node_t angle_compensate_nodes[angle_compensate_nodes_count];
00226 memset(angle_compensate_nodes, 0, angle_compensate_nodes_count*sizeof(rplidar_response_measurement_node_t));
00227 int i = 0, j = 0;
00228 for( ; i < count; i++ ) {
00229 if (nodes[i].distance_q2 != 0) {
00230 float angle = (float)((nodes[i].angle_q6_checkbit >> RPLIDAR_RESP_MEASUREMENT_ANGLE_SHIFT)/64.0f);
00231 int angle_value = (int)(angle * angle_compensate_multiple);
00232 if ((angle_value - angle_compensate_offset) < 0) angle_compensate_offset = angle_value;
00233 for (j = 0; j < angle_compensate_multiple; j++) {
00234 angle_compensate_nodes[angle_value-angle_compensate_offset+j] = nodes[i];
00235 }
00236 }
00237 }
00238
00239 publish_scan(&scan_pub, angle_compensate_nodes, angle_compensate_nodes_count,
00240 start_scan_time, scan_duration, inverted,
00241 angle_min, angle_max,
00242 frame_id);
00243 } else {
00244 int start_node = 0, end_node = 0;
00245 int i = 0;
00246
00247 while (nodes[i++].distance_q2 == 0);
00248 start_node = i-1;
00249 i = count -1;
00250 while (nodes[i--].distance_q2 == 0);
00251 end_node = i+1;
00252
00253 angle_min = DEG2RAD((float)(nodes[start_node].angle_q6_checkbit >> RPLIDAR_RESP_MEASUREMENT_ANGLE_SHIFT)/64.0f);
00254 angle_max = DEG2RAD((float)(nodes[end_node].angle_q6_checkbit >> RPLIDAR_RESP_MEASUREMENT_ANGLE_SHIFT)/64.0f);
00255
00256 publish_scan(&scan_pub, &nodes[start_node], end_node-start_node +1,
00257 start_scan_time, scan_duration, inverted,
00258 angle_min, angle_max,
00259 frame_id);
00260 }
00261 } else if (op_result == RESULT_OPERATION_FAIL) {
00262
00263 float angle_min = DEG2RAD(0.0f);
00264 float angle_max = DEG2RAD(359.0f);
00265
00266 publish_scan(&scan_pub, nodes, count,
00267 start_scan_time, scan_duration, inverted,
00268 angle_min, angle_max,
00269 frame_id);
00270 }
00271 }
00272
00273 ros::spinOnce();
00274 }
00275
00276
00277 RPlidarDriver::DisposeDriver(drv);
00278 return 0;
00279 }