node.cpp
Go to the documentation of this file.
00001 /*
00002  *  RPLIDAR ROS NODE
00003  *
00004  *  Copyright (c) 2009 - 2014 RoboPeak Team
00005  *  http://www.robopeak.com
00006  *  Copyright (c) 2014 - 2016 Shanghai Slamtec Co., Ltd.
00007  *  http://www.slamtec.com
00008  *
00009  */
00010 /*
00011  * Redistribution and use in source and binary forms, with or without
00012  * modification, are permitted provided that the following conditions are met:
00013  *
00014  * 1. Redistributions of source code must retain the above copyright notice,
00015  *    this list of conditions and the following disclaimer.
00016  *
00017  * 2. Redistributions in binary form must reproduce the above copyright notice,
00018  *    this list of conditions and the following disclaimer in the documentation
00019  *    and/or other materials provided with the distribution.
00020  *
00021  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00022  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO,
00023  * THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
00024  * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
00025  * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
00026  * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
00027  * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS;
00028  * OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
00029  * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR
00030  * OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
00031  * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00032  *
00033  */
00034 
00035 #include "ros/ros.h"
00036 #include "sensor_msgs/LaserScan.h"
00037 #include "std_srvs/Empty.h"
00038 #include "rplidar.h"
00039 
00040 #ifndef _countof
00041 #define _countof(_Array) (int)(sizeof(_Array) / sizeof(_Array[0]))
00042 #endif
00043 
00044 #define DEG2RAD(x) ((x)*M_PI/180.)
00045 
00046 using namespace rp::standalone::rplidar;
00047 
00048 RPlidarDriver * drv = NULL;
00049 
00050 void publish_scan(ros::Publisher *pub,
00051                   rplidar_response_measurement_node_t *nodes,
00052                   size_t node_count, ros::Time start,
00053                   double scan_time, bool inverted,
00054                   float angle_min, float angle_max,
00055                   std::string frame_id)
00056 {
00057     static int scan_count = 0;
00058     sensor_msgs::LaserScan scan_msg;
00059 
00060     scan_msg.header.stamp = start;
00061     scan_msg.header.frame_id = frame_id;
00062     scan_count++;
00063 
00064     bool reversed = (angle_max > angle_min);
00065     if ( reversed ) {
00066       scan_msg.angle_min =  M_PI - angle_max;
00067       scan_msg.angle_max =  M_PI - angle_min;
00068     } else {
00069       scan_msg.angle_min =  M_PI - angle_min;
00070       scan_msg.angle_max =  M_PI - angle_max;
00071     }
00072     scan_msg.angle_increment =
00073         (scan_msg.angle_max - scan_msg.angle_min) / (double)(node_count-1);
00074 
00075     scan_msg.scan_time = scan_time;
00076     scan_msg.time_increment = scan_time / (double)(node_count-1);
00077     scan_msg.range_min = 0.15;
00078     scan_msg.range_max = 8.0;
00079 
00080     scan_msg.intensities.resize(node_count);
00081     scan_msg.ranges.resize(node_count);
00082     bool reverse_data = (!inverted && reversed) || (inverted && !reversed);
00083     if (!reverse_data) {
00084         for (size_t i = 0; i < node_count; i++) {
00085             float read_value = (float) nodes[i].distance_q2/4.0f/1000;
00086             if (read_value == 0.0)
00087                 scan_msg.ranges[i] = std::numeric_limits<float>::infinity();
00088             else
00089                 scan_msg.ranges[i] = read_value;
00090             scan_msg.intensities[i] = (float) (nodes[i].sync_quality >> 2);
00091         }
00092     } else {
00093         for (size_t i = 0; i < node_count; i++) {
00094             float read_value = (float)nodes[i].distance_q2/4.0f/1000;
00095             if (read_value == 0.0)
00096                 scan_msg.ranges[node_count-1-i] = std::numeric_limits<float>::infinity();
00097             else
00098                 scan_msg.ranges[node_count-1-i] = read_value;
00099             scan_msg.intensities[node_count-1-i] = (float) (nodes[i].sync_quality >> 2);
00100         }
00101     }
00102 
00103     pub->publish(scan_msg);
00104 }
00105 
00106 bool getRPLIDARDeviceInfo(RPlidarDriver * drv)
00107 {
00108     u_result     op_result;
00109     rplidar_response_device_info_t devinfo;
00110 
00111     op_result = drv->getDeviceInfo(devinfo);
00112     if (IS_FAIL(op_result)) {
00113         if (op_result == RESULT_OPERATION_TIMEOUT) {
00114             fprintf(stderr, "Error, operation time out.\n");
00115         } else {
00116             fprintf(stderr, "Error, unexpected error, code: %x\n", op_result);
00117         }
00118         return false;
00119     }
00120 
00121     // print out the device serial number, firmware and hardware version number..
00122     printf("RPLIDAR S/N: ");
00123     for (int pos = 0; pos < 16 ;++pos) {
00124         printf("%02X", devinfo.serialnum[pos]);
00125     }
00126 
00127     printf("\n"
00128            "Firmware Ver: %d.%02d\n"
00129            "Hardware Rev: %d\n"
00130            , devinfo.firmware_version>>8
00131            , devinfo.firmware_version & 0xFF
00132            , (int)devinfo.hardware_version);
00133     return true;
00134 }
00135 
00136 bool checkRPLIDARHealth(RPlidarDriver * drv)
00137 {
00138     u_result     op_result;
00139     rplidar_response_device_health_t healthinfo;
00140 
00141     op_result = drv->getHealth(healthinfo);
00142     if (IS_OK(op_result)) { 
00143         printf("RPLidar health status : %d\n", healthinfo.status);
00144         
00145         if (healthinfo.status == RPLIDAR_STATUS_ERROR) {
00146             fprintf(stderr, "Error, rplidar internal error detected."
00147                             "Please reboot the device to retry.\n");
00148             return false;
00149         } else {
00150             return true;
00151         }
00152 
00153     } else {
00154         fprintf(stderr, "Error, cannot retrieve rplidar health code: %x\n", 
00155                         op_result);
00156         return false;
00157     }
00158 }
00159 
00160 bool stop_motor(std_srvs::Empty::Request &req,
00161                                std_srvs::Empty::Response &res)
00162 {
00163   if(!drv)
00164        return false;
00165 
00166   ROS_DEBUG("Stop motor");
00167   drv->stop();
00168   drv->stopMotor();
00169   return true;
00170 }
00171 
00172 bool start_motor(std_srvs::Empty::Request &req,
00173                                std_srvs::Empty::Response &res)
00174 {
00175   if(!drv)
00176        return false;
00177   ROS_DEBUG("Start motor");
00178   drv->startMotor();
00179   drv->startScan();;
00180   return true;
00181 }
00182 
00183 int main(int argc, char * argv[]) {
00184     ros::init(argc, argv, "rplidar_node");
00185 
00186     std::string serial_port;
00187     int serial_baudrate = 115200;
00188     std::string frame_id;
00189     bool inverted = false;
00190     bool angle_compensate = true;
00191 
00192     ros::NodeHandle nh;
00193     ros::Publisher scan_pub = nh.advertise<sensor_msgs::LaserScan>("scan", 1000);
00194     ros::NodeHandle nh_private("~");
00195     nh_private.param<std::string>("serial_port", serial_port, "/dev/ttyUSB0"); 
00196     nh_private.param<int>("serial_baudrate", serial_baudrate, 115200); 
00197     nh_private.param<std::string>("frame_id", frame_id, "laser_frame");
00198     nh_private.param<bool>("inverted", inverted, false);
00199     nh_private.param<bool>("angle_compensate", angle_compensate, true);
00200 
00201     printf("RPLIDAR running on ROS package rplidar_ros\n"
00202            "SDK Version: "RPLIDAR_SDK_VERSION"\n");
00203 
00204     u_result     op_result;
00205 
00206     // create the driver instance
00207     drv = RPlidarDriver::CreateDriver(RPlidarDriver::DRIVER_TYPE_SERIALPORT);
00208     
00209     if (!drv) {
00210         fprintf(stderr, "Create Driver fail, exit\n");
00211         return -2;
00212     }
00213 
00214     // make connection...
00215     if (IS_FAIL(drv->connect(serial_port.c_str(), (_u32)serial_baudrate))) {
00216         fprintf(stderr, "Error, cannot bind to the specified serial port %s.\n"
00217             , serial_port.c_str());
00218         RPlidarDriver::DisposeDriver(drv);
00219         return -1;
00220     }
00221 
00222     // get rplidar device info
00223     if (!getRPLIDARDeviceInfo(drv)) {
00224         return -1;
00225     }
00226 
00227     // check health...
00228     if (!checkRPLIDARHealth(drv)) {
00229         RPlidarDriver::DisposeDriver(drv);
00230         return -1;
00231     }
00232 
00233     ros::ServiceServer stop_motor_service = nh.advertiseService("stop_motor", stop_motor);
00234     ros::ServiceServer start_motor_service = nh.advertiseService("start_motor", start_motor);
00235 
00236     drv->startMotor();
00237     drv->startScan();
00238 
00239     ros::Time start_scan_time;
00240     ros::Time end_scan_time;
00241     double scan_duration;
00242     while (ros::ok()) {
00243 
00244         rplidar_response_measurement_node_t nodes[360*2];
00245         size_t   count = _countof(nodes);
00246 
00247         start_scan_time = ros::Time::now();
00248         op_result = drv->grabScanData(nodes, count);
00249         end_scan_time = ros::Time::now();
00250         scan_duration = (end_scan_time - start_scan_time).toSec() * 1e-3;
00251 
00252         if (op_result == RESULT_OK) {
00253             op_result = drv->ascendScanData(nodes, count);
00254 
00255             float angle_min = DEG2RAD(0.0f);
00256             float angle_max = DEG2RAD(359.0f);
00257             if (op_result == RESULT_OK) {
00258                 if (angle_compensate) {
00259                     const int angle_compensate_nodes_count = 360;
00260                     const int angle_compensate_multiple = 1;
00261                     int angle_compensate_offset = 0;
00262                     rplidar_response_measurement_node_t angle_compensate_nodes[angle_compensate_nodes_count];
00263                     memset(angle_compensate_nodes, 0, angle_compensate_nodes_count*sizeof(rplidar_response_measurement_node_t));
00264                     int i = 0, j = 0;
00265                     for( ; i < count; i++ ) {
00266                         if (nodes[i].distance_q2 != 0) {
00267                             float angle = (float)((nodes[i].angle_q6_checkbit >> RPLIDAR_RESP_MEASUREMENT_ANGLE_SHIFT)/64.0f);
00268                             int angle_value = (int)(angle * angle_compensate_multiple);
00269                             if ((angle_value - angle_compensate_offset) < 0) angle_compensate_offset = angle_value;
00270                             for (j = 0; j < angle_compensate_multiple; j++) {
00271                                 angle_compensate_nodes[angle_value-angle_compensate_offset+j] = nodes[i];
00272                             }
00273                         }
00274                     }
00275   
00276                     publish_scan(&scan_pub, angle_compensate_nodes, angle_compensate_nodes_count,
00277                              start_scan_time, scan_duration, inverted,
00278                              angle_min, angle_max,
00279                              frame_id);
00280                 } else {
00281                     int start_node = 0, end_node = 0;
00282                     int i = 0;
00283                     // find the first valid node and last valid node
00284                     while (nodes[i++].distance_q2 == 0);
00285                     start_node = i-1;
00286                     i = count -1;
00287                     while (nodes[i--].distance_q2 == 0);
00288                     end_node = i+1;
00289 
00290                     angle_min = DEG2RAD((float)(nodes[start_node].angle_q6_checkbit >> RPLIDAR_RESP_MEASUREMENT_ANGLE_SHIFT)/64.0f);
00291                     angle_max = DEG2RAD((float)(nodes[end_node].angle_q6_checkbit >> RPLIDAR_RESP_MEASUREMENT_ANGLE_SHIFT)/64.0f);
00292 
00293                     publish_scan(&scan_pub, &nodes[start_node], end_node-start_node +1,
00294                              start_scan_time, scan_duration, inverted,
00295                              angle_min, angle_max,
00296                              frame_id);
00297                }
00298             } else if (op_result == RESULT_OPERATION_FAIL) {
00299                 // All the data is invalid, just publish them
00300                 float angle_min = DEG2RAD(0.0f);
00301                 float angle_max = DEG2RAD(359.0f);
00302 
00303                 publish_scan(&scan_pub, nodes, count,
00304                              start_scan_time, scan_duration, inverted,
00305                              angle_min, angle_max,
00306                              frame_id);
00307             }
00308         }
00309 
00310         ros::spinOnce();
00311     }
00312 
00313     // done!
00314     drv->stop();
00315     drv->stopMotor();
00316     RPlidarDriver::DisposeDriver(drv);
00317     return 0;
00318 }


rplidar_ros
Author(s):
autogenerated on Fri Dec 16 2016 03:59:16