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_hq_t *nodes,
00052                   size_t node_count, ros::Time start,
00053                   double scan_time, bool inverted,
00054                   float angle_min, float angle_max,
00055                   float max_distance,
00056                   std::string frame_id)
00057 {
00058     static int scan_count = 0;
00059     sensor_msgs::LaserScan scan_msg;
00060 
00061     scan_msg.header.stamp = start;
00062     scan_msg.header.frame_id = frame_id;
00063     scan_count++;
00064 
00065     bool reversed = (angle_max > angle_min);
00066     if ( reversed ) {
00067       scan_msg.angle_min =  M_PI - angle_max;
00068       scan_msg.angle_max =  M_PI - angle_min;
00069     } else {
00070       scan_msg.angle_min =  M_PI - angle_min;
00071       scan_msg.angle_max =  M_PI - angle_max;
00072     }
00073     scan_msg.angle_increment =
00074         (scan_msg.angle_max - scan_msg.angle_min) / (double)(node_count-1);
00075 
00076     scan_msg.scan_time = scan_time;
00077     scan_msg.time_increment = scan_time / (double)(node_count-1);
00078     scan_msg.range_min = 0.15;
00079     scan_msg.range_max = max_distance;//8.0;
00080 
00081     scan_msg.intensities.resize(node_count);
00082     scan_msg.ranges.resize(node_count);
00083     bool reverse_data = (!inverted && reversed) || (inverted && !reversed);
00084     if (!reverse_data) {
00085         for (size_t i = 0; i < node_count; i++) {
00086             float read_value = (float) nodes[i].dist_mm_q2/4.0f/1000;
00087             if (read_value == 0.0)
00088                 scan_msg.ranges[i] = std::numeric_limits<float>::infinity();
00089             else
00090                 scan_msg.ranges[i] = read_value;
00091             scan_msg.intensities[i] = (float) (nodes[i].quality >> 2);
00092         }
00093     } else {
00094         for (size_t i = 0; i < node_count; i++) {
00095             float read_value = (float)nodes[i].dist_mm_q2/4.0f/1000;
00096             if (read_value == 0.0)
00097                 scan_msg.ranges[node_count-1-i] = std::numeric_limits<float>::infinity();
00098             else
00099                 scan_msg.ranges[node_count-1-i] = read_value;
00100             scan_msg.intensities[node_count-1-i] = (float) (nodes[i].quality >> 2);
00101         }
00102     }
00103 
00104     pub->publish(scan_msg);
00105 }
00106 
00107 bool getRPLIDARDeviceInfo(RPlidarDriver * drv)
00108 {
00109     u_result     op_result;
00110     rplidar_response_device_info_t devinfo;
00111 
00112     op_result = drv->getDeviceInfo(devinfo);
00113     if (IS_FAIL(op_result)) {
00114         if (op_result == RESULT_OPERATION_TIMEOUT) {
00115             ROS_ERROR("Error, operation time out. RESULT_OPERATION_TIMEOUT! ");
00116         } else {
00117             ROS_ERROR("Error, unexpected error, code: %x",op_result);
00118         }
00119         return false;
00120     }
00121 
00122     // print out the device serial number, firmware and hardware version number..
00123     printf("RPLIDAR S/N: ");
00124     for (int pos = 0; pos < 16 ;++pos) {
00125         printf("%02X", devinfo.serialnum[pos]);
00126     }
00127     printf("\n");
00128     ROS_INFO("Firmware Ver: %d.%02d",devinfo.firmware_version>>8, devinfo.firmware_version & 0xFF);
00129     ROS_INFO("Hardware Rev: %d",(int)devinfo.hardware_version);
00130     return true;
00131 }
00132 
00133 bool checkRPLIDARHealth(RPlidarDriver * drv)
00134 {
00135     u_result     op_result;
00136     rplidar_response_device_health_t healthinfo;
00137 
00138     op_result = drv->getHealth(healthinfo);
00139     if (IS_OK(op_result)) { 
00140         ROS_INFO("RPLidar health status : %d", healthinfo.status);
00141         if (healthinfo.status == RPLIDAR_STATUS_ERROR) {
00142             ROS_ERROR("Error, rplidar internal error detected. Please reboot the device to retry.");
00143             return false;
00144         } else {
00145             return true;
00146         }
00147 
00148     } else {
00149         ROS_ERROR("Error, cannot retrieve rplidar health code: %x", op_result);
00150         return false;
00151     }
00152 }
00153 
00154 bool stop_motor(std_srvs::Empty::Request &req,
00155                                std_srvs::Empty::Response &res)
00156 {
00157   if(!drv)
00158        return false;
00159 
00160   ROS_DEBUG("Stop motor");
00161   drv->stop();
00162   drv->stopMotor();
00163   return true;
00164 }
00165 
00166 bool start_motor(std_srvs::Empty::Request &req,
00167                                std_srvs::Empty::Response &res)
00168 {
00169   if(!drv)
00170        return false;
00171   ROS_DEBUG("Start motor");
00172   drv->startMotor();
00173   drv->startScan(0,1);
00174   return true;
00175 }
00176 
00177 static float getAngle(const rplidar_response_measurement_node_hq_t& node)
00178 {
00179     return node.angle_z_q14 * 90.f / 16384.f;
00180 }
00181 
00182 int main(int argc, char * argv[]) {
00183     ros::init(argc, argv, "rplidar_node");
00184     
00185     std::string channel_type;
00186     std::string tcp_ip;
00187     std::string serial_port;
00188     int tcp_port = 20108;
00189     int serial_baudrate = 115200;
00190     std::string frame_id;
00191     bool inverted = false;
00192     bool angle_compensate = true;
00193     float max_distance = 8.0;
00194     int angle_compensate_multiple = 1;//it stand of angle compensate at per 1 degree
00195     std::string scan_mode;
00196     ros::NodeHandle nh;
00197     ros::Publisher scan_pub = nh.advertise<sensor_msgs::LaserScan>("scan", 1000);
00198     ros::NodeHandle nh_private("~");
00199     nh_private.param<std::string>("channel_type", channel_type, "serial");
00200     nh_private.param<std::string>("tcp_ip", tcp_ip, "192.168.0.7"); 
00201     nh_private.param<int>("tcp_port", tcp_port, 20108);
00202     nh_private.param<std::string>("serial_port", serial_port, "/dev/ttyUSB0"); 
00203     nh_private.param<int>("serial_baudrate", serial_baudrate, 115200/*256000*/);//ros run for A1 A2, change to 256000 if A3
00204     nh_private.param<std::string>("frame_id", frame_id, "laser_frame");
00205     nh_private.param<bool>("inverted", inverted, false);
00206     nh_private.param<bool>("angle_compensate", angle_compensate, false);
00207     nh_private.param<std::string>("scan_mode", scan_mode, std::string());
00208 
00209     ROS_INFO("RPLIDAR running on ROS package rplidar_ros. SDK Version:"RPLIDAR_SDK_VERSION"");
00210 
00211     u_result     op_result;
00212 
00213     // create the driver instance
00214     if(channel_type == "tcp"){
00215         drv = RPlidarDriver::CreateDriver(rp::standalone::rplidar::DRIVER_TYPE_TCP);
00216     }
00217     else{
00218         drv = RPlidarDriver::CreateDriver(rp::standalone::rplidar::DRIVER_TYPE_SERIALPORT);
00219     }
00220 
00221     
00222     if (!drv) {
00223         ROS_ERROR("Create Driver fail, exit");
00224         return -2;
00225     }
00226 
00227     if(channel_type == "tcp"){
00228         // make connection...
00229         if (IS_FAIL(drv->connect(tcp_ip.c_str(), (_u32)tcp_port))) {
00230             ROS_ERROR("Error, cannot bind to the specified serial port %s.",serial_port.c_str());
00231             RPlidarDriver::DisposeDriver(drv);
00232             return -1;
00233         }
00234 
00235     }
00236     else{
00237        // make connection...
00238         if (IS_FAIL(drv->connect(serial_port.c_str(), (_u32)serial_baudrate))) {
00239             ROS_ERROR("Error, cannot bind to the specified serial port %s.",serial_port.c_str());
00240             RPlidarDriver::DisposeDriver(drv);
00241             return -1;
00242         }
00243 
00244     }
00245     
00246     // get rplidar device info
00247     if (!getRPLIDARDeviceInfo(drv)) {
00248         return -1;
00249     }
00250 
00251     // check health...
00252     if (!checkRPLIDARHealth(drv)) {
00253         RPlidarDriver::DisposeDriver(drv);
00254         return -1;
00255     }
00256 
00257     ros::ServiceServer stop_motor_service = nh.advertiseService("stop_motor", stop_motor);
00258     ros::ServiceServer start_motor_service = nh.advertiseService("start_motor", start_motor);
00259 
00260     drv->startMotor();
00261 
00262     RplidarScanMode current_scan_mode;
00263     if (scan_mode.empty()) {
00264         op_result = drv->startScan(false /* not force scan */, true /* use typical scan mode */, 0, &current_scan_mode);
00265     } else {
00266         std::vector<RplidarScanMode> allSupportedScanModes;
00267         op_result = drv->getAllSupportedScanModes(allSupportedScanModes);
00268 
00269         if (IS_OK(op_result)) {
00270             _u16 selectedScanMode = _u16(-1);
00271             for (std::vector<RplidarScanMode>::iterator iter = allSupportedScanModes.begin(); iter != allSupportedScanModes.end(); iter++) {
00272                 if (iter->scan_mode == scan_mode) {
00273                     selectedScanMode = iter->id;
00274                     break;
00275                 }
00276             }
00277 
00278             if (selectedScanMode == _u16(-1)) {
00279                 ROS_ERROR("scan mode `%s' is not supported by lidar, supported modes:", scan_mode.c_str());
00280                 for (std::vector<RplidarScanMode>::iterator iter = allSupportedScanModes.begin(); iter != allSupportedScanModes.end(); iter++) {
00281                     ROS_ERROR("\t%s: max_distance: %.1f m, Point number: %.1fK",  iter->scan_mode,
00282                             iter->max_distance, (1000/iter->us_per_sample));
00283                 }
00284                 op_result = RESULT_OPERATION_FAIL;
00285             } else {
00286                 op_result = drv->startScanExpress(false /* not force scan */, selectedScanMode, 0, &current_scan_mode);
00287             }
00288         }
00289     }
00290 
00291     if(IS_OK(op_result))
00292     {
00293         //default frequent is 10 hz (by motor pwm value),  current_scan_mode.us_per_sample is the number of scan point per us
00294         angle_compensate_multiple = (int)(1000*1000/current_scan_mode.us_per_sample/10.0/360.0);
00295         if(angle_compensate_multiple < 1) 
00296           angle_compensate_multiple = 1;
00297         max_distance = current_scan_mode.max_distance;
00298         ROS_INFO("current scan mode: %s, max_distance: %.1f m, Point number: %.1fK , angle_compensate: %d",  current_scan_mode.scan_mode,
00299                  current_scan_mode.max_distance, (1000/current_scan_mode.us_per_sample), angle_compensate_multiple);
00300     }
00301     else
00302     {
00303         ROS_ERROR("Can not start scan: %08x!", op_result);
00304     }
00305 
00306     ros::Time start_scan_time;
00307     ros::Time end_scan_time;
00308     double scan_duration;
00309     while (ros::ok()) {
00310         rplidar_response_measurement_node_hq_t nodes[360*8];
00311         size_t   count = _countof(nodes);
00312 
00313         start_scan_time = ros::Time::now();
00314         op_result = drv->grabScanDataHq(nodes, count);
00315         end_scan_time = ros::Time::now();
00316         scan_duration = (end_scan_time - start_scan_time).toSec();
00317 
00318         if (op_result == RESULT_OK) {
00319             op_result = drv->ascendScanData(nodes, count);
00320             float angle_min = DEG2RAD(0.0f);
00321             float angle_max = DEG2RAD(359.0f);
00322             if (op_result == RESULT_OK) {
00323                 if (angle_compensate) {
00324                     //const int angle_compensate_multiple = 1;
00325                     const int angle_compensate_nodes_count = 360*angle_compensate_multiple;
00326                     int angle_compensate_offset = 0;
00327                     rplidar_response_measurement_node_hq_t angle_compensate_nodes[angle_compensate_nodes_count];
00328                     memset(angle_compensate_nodes, 0, angle_compensate_nodes_count*sizeof(rplidar_response_measurement_node_hq_t));
00329 
00330                     int i = 0, j = 0;
00331                     for( ; i < count; i++ ) {
00332                         if (nodes[i].dist_mm_q2 != 0) {
00333                             float angle = getAngle(nodes[i]);
00334                             int angle_value = (int)(angle * angle_compensate_multiple);
00335                             if ((angle_value - angle_compensate_offset) < 0) angle_compensate_offset = angle_value;
00336                             for (j = 0; j < angle_compensate_multiple; j++) {
00337                                 angle_compensate_nodes[angle_value-angle_compensate_offset+j] = nodes[i];
00338                             }
00339                         }
00340                     }
00341   
00342                     publish_scan(&scan_pub, angle_compensate_nodes, angle_compensate_nodes_count,
00343                              start_scan_time, scan_duration, inverted,
00344                              angle_min, angle_max, max_distance,
00345                              frame_id);
00346                 } else {
00347                     int start_node = 0, end_node = 0;
00348                     int i = 0;
00349                     // find the first valid node and last valid node
00350                     while (nodes[i++].dist_mm_q2 == 0);
00351                     start_node = i-1;
00352                     i = count -1;
00353                     while (nodes[i--].dist_mm_q2 == 0);
00354                     end_node = i+1;
00355 
00356                     angle_min = DEG2RAD(getAngle(nodes[start_node]));
00357                     angle_max = DEG2RAD(getAngle(nodes[end_node]));
00358 
00359                     publish_scan(&scan_pub, &nodes[start_node], end_node-start_node +1,
00360                              start_scan_time, scan_duration, inverted,
00361                              angle_min, angle_max, max_distance,
00362                              frame_id);
00363                }
00364             } else if (op_result == RESULT_OPERATION_FAIL) {
00365                 // All the data is invalid, just publish them
00366                 float angle_min = DEG2RAD(0.0f);
00367                 float angle_max = DEG2RAD(359.0f);
00368 
00369                 publish_scan(&scan_pub, nodes, count,
00370                              start_scan_time, scan_duration, inverted,
00371                              angle_min, angle_max, max_distance,
00372                              frame_id);
00373             }
00374         }
00375 
00376         ros::spinOnce();
00377     }
00378 
00379     // done!
00380     drv->stop();
00381     drv->stopMotor();
00382     RPlidarDriver::DisposeDriver(drv);
00383     return 0;
00384 }


rplidar_ros
Author(s):
autogenerated on Mon Mar 18 2019 02:34:23