原创博客:转载请表明出处:http://www.cnblogs.com/zxouxuewei/

由于市面上买的激光雷达价格太贵了。所以在学习时会造成很大的经济压力。但是最近好多做机器人核心组件的公司都开发有廉价的雷达;

本博客教你如何 使用rplidar发布scan数据,在rviz视图中查看scan数据。

1.首先确保你的rplidar水平放置在你的机器人上:(注意安装方向)

2.然后下载rplidar的rosSDK开发包,

3.初步测试:

运行roscore

roscore &

直接运行rplidar的launch文件

roslaunch rplidar_ros view_rplidar.launch 

查看view_rplidar.launch文件

<!--
Used for visualising rplidar in action. It requires rplidar.launch.
-->
<launch>
<include file="$(find rplidar_ros)/launch/rplidar.launch" /> <node name="rviz" pkg="rviz" type="rviz" args="-d $(find rplidar_ros)/rviz/rplidar.rviz" />
</launch>

主要是查看rplidar.launch文件

<launch>
<node name="rplidarNode" pkg="rplidar_ros" type="rplidarNode" output="screen">
<param name="serial_port" type="string" value="/dev/ttyUSB0"/>
<param name="serial_baudrate" type="int" value=""/>
<param name="frame_id" type="string" value="laser"/>
<param name="inverted" type="bool" value="false"/>
<param name="angle_compensate" type="bool" value="true"/>
</node>
</launch>

在这个launch文件中打开了rplidarNode这个节点,然后我们分析一下节点源码:

#include "ros/ros.h"
#include "sensor_msgs/LaserScan.h"
#include "std_srvs/Empty.h" #include "rplidar.h" //RPLIDAR standard sdk, all-in-one header #ifndef _countof
#define _countof(_Array) (int)(sizeof(_Array) / sizeof(_Array[0]))
#endif #define DEG2RAD(x) ((x)*M_PI/180.) using namespace rp::standalone::rplidar; RPlidarDriver * drv = NULL; void publish_scan(ros::Publisher *pub,
rplidar_response_measurement_node_t *nodes,
size_t node_count, ros::Time start,
double scan_time, bool inverted,
float angle_min, float angle_max,
std::string frame_id)
{
static int scan_count = ;
sensor_msgs::LaserScan scan_msg; scan_msg.header.stamp = start;
scan_msg.header.frame_id = frame_id;
scan_count++; scan_msg.angle_min = M_PI - angle_min;
scan_msg.angle_max = M_PI - angle_max;
scan_msg.angle_increment =
(scan_msg.angle_max - scan_msg.angle_min) / (double)(node_count-); scan_msg.scan_time = scan_time;
scan_msg.time_increment = scan_time / (double)(node_count-); scan_msg.range_min = 0.15;
scan_msg.range_max = .; scan_msg.intensities.resize(node_count);
scan_msg.ranges.resize(node_count);
if (!inverted) { // assumes scan window at the top
for (size_t i = ; i < node_count; i++) {
float read_value = (float) nodes[i].distance_q2/4.0f/;
if (read_value == 0.0)
scan_msg.ranges[i] = std::numeric_limits<float>::infinity();
else
scan_msg.ranges[i] = read_value;
scan_msg.intensities[i] = (float) (nodes[i].sync_quality >> );
}
} else {
for (size_t i = ; i < node_count; i++) {
float read_value = (float)nodes[i].distance_q2/4.0f/;
if (read_value == 0.0)
scan_msg.ranges[node_count--i] = std::numeric_limits<float>::infinity();
else
scan_msg.ranges[node_count--i] = read_value;
scan_msg.intensities[node_count--i] = (float) (nodes[i].sync_quality >> );
}
} pub->publish(scan_msg);
} bool checkRPLIDARHealth(RPlidarDriver * drv)
{
u_result op_result;
rplidar_response_device_health_t healthinfo; op_result = drv->getHealth(healthinfo);
if (IS_OK(op_result)) {
printf("RPLidar health status : %d\n", healthinfo.status); if (healthinfo.status == RPLIDAR_STATUS_ERROR) {
fprintf(stderr, "Error, rplidar internal error detected."
"Please reboot the device to retry.\n");
return false;
} else {
return true;
} } else {
fprintf(stderr, "Error, cannot retrieve rplidar health code: %x\n",
op_result);
return false;
}
} bool stop_motor(std_srvs::Empty::Request &req,
std_srvs::Empty::Response &res)
{
if(!drv)
return false; ROS_DEBUG("Stop motor");
drv->stop();
drv->stopMotor();
return true;
} bool start_motor(std_srvs::Empty::Request &req,
std_srvs::Empty::Response &res)
{
if(!drv)
return false;
ROS_DEBUG("Start motor");
drv->startMotor();
drv->startScan();;
return true;
} int main(int argc, char * argv[]) {
ros::init(argc, argv, "rplidar_node"); std::string serial_port;
int serial_baudrate = ;
std::string frame_id;
bool inverted = false;
bool angle_compensate = true; ros::NodeHandle nh;
ros::Publisher scan_pub = nh.advertise<sensor_msgs::LaserScan>("scan", );
ros::NodeHandle nh_private("~");
nh_private.param<std::string>("serial_port", serial_port, "/dev/ttyUSB0");
nh_private.param<int>("serial_baudrate", serial_baudrate, );
nh_private.param<std::string>("frame_id", frame_id, "laser_frame");
nh_private.param<bool>("inverted", inverted, "false");
nh_private.param<bool>("angle_compensate", angle_compensate, "true"); u_result op_result; // create the driver instance
drv = RPlidarDriver::CreateDriver(RPlidarDriver::DRIVER_TYPE_SERIALPORT); if (!drv) {
fprintf(stderr, "Create Driver fail, exit\n");
return -;
} // make connection...
if (IS_FAIL(drv->connect(serial_port.c_str(), (_u32)serial_baudrate))) {
fprintf(stderr, "Error, cannot bind to the specified serial port %s.\n"
, serial_port.c_str());
RPlidarDriver::DisposeDriver(drv);
return -;
} // check health...
if (!checkRPLIDARHealth(drv)) {
RPlidarDriver::DisposeDriver(drv);
return -;
} ros::ServiceServer stop_motor_service = nh.advertiseService("stop_motor", stop_motor);
ros::ServiceServer start_motor_service = nh.advertiseService("start_motor", start_motor); // start scan...
drv->startScan(); ros::Time start_scan_time;
ros::Time end_scan_time;
double scan_duration;
while (ros::ok()) { rplidar_response_measurement_node_t nodes[*];
size_t count = _countof(nodes); start_scan_time = ros::Time::now();
op_result = drv->grabScanData(nodes, count);
end_scan_time = ros::Time::now();
scan_duration = (end_scan_time - start_scan_time).toSec() * 1e-; if (op_result == RESULT_OK) {
op_result = drv->ascendScanData(nodes, count); float angle_min = DEG2RAD(0.0f);
float angle_max = DEG2RAD(359.0f);
if (op_result == RESULT_OK) {
if (angle_compensate) {
const int angle_compensate_nodes_count = ;
const int angle_compensate_multiple = ;
int angle_compensate_offset = ;
rplidar_response_measurement_node_t angle_compensate_nodes[angle_compensate_nodes_count];
memset(angle_compensate_nodes, , angle_compensate_nodes_count*sizeof(rplidar_response_measurement_node_t));
int i = , j = ;
for( ; i < count; i++ ) {
if (nodes[i].distance_q2 != ) {
float angle = (float)((nodes[i].angle_q6_checkbit >> RPLIDAR_RESP_MEASUREMENT_ANGLE_SHIFT)/64.0f);
int angle_value = (int)(angle * angle_compensate_multiple);
if ((angle_value - angle_compensate_offset) < ) angle_compensate_offset = angle_value;
for (j = ; j < angle_compensate_multiple; j++) {
angle_compensate_nodes[angle_value-angle_compensate_offset+j] = nodes[i];
}
}
} publish_scan(&scan_pub, angle_compensate_nodes, angle_compensate_nodes_count,
start_scan_time, scan_duration, inverted,
angle_min, angle_max,
frame_id);
} else {
int start_node = , end_node = ;
int i = ;
// find the first valid node and last valid node
while (nodes[i++].distance_q2 == );
start_node = i-;
i = count -;
while (nodes[i--].distance_q2 == );
end_node = i+; angle_min = DEG2RAD((float)(nodes[start_node].angle_q6_checkbit >> RPLIDAR_RESP_MEASUREMENT_ANGLE_SHIFT)/64.0f);
angle_max = DEG2RAD((float)(nodes[end_node].angle_q6_checkbit >> RPLIDAR_RESP_MEASUREMENT_ANGLE_SHIFT)/64.0f); publish_scan(&scan_pub, &nodes[start_node], end_node-start_node +,
start_scan_time, scan_duration, inverted,
angle_min, angle_max,
frame_id);
}
} else if (op_result == RESULT_OPERATION_FAIL) {
// All the data is invalid, just publish them
float angle_min = DEG2RAD(0.0f);
float angle_max = DEG2RAD(359.0f); publish_scan(&scan_pub, nodes, count,
start_scan_time, scan_duration, inverted,
angle_min, angle_max,
frame_id);
}
} ros::spinOnce();
} // done!
RPlidarDriver::DisposeDriver(drv);
return ;
}

主要是打开串口读取rplidar的数据,然后发布scan话题。

查看rqt_graph节点视图。

在ros中使用rplidar Laser发布scan数据--25的更多相关文章

  1. ROS中发布激光扫描消息

    激光雷达工作时会先在当前位置发出激光并接收反射光束,解析得到距离信息,而后激光发射器会转过一个角度分辨率对应的角度再次重复这个过程.限于物理及机械方面的限制,激光雷达通常会有一部分“盲区”.使用激光雷 ...

  2. Rplidar学习(四)—— ROS下进行rplidar雷达数据采集源码分析

    一.子函数分析 1.发布数据子函数 (1)雷达数据数据类型 Header header # timestamp in the header is the acquisition time of # t ...

  3. ROS中利用V-rep进行地图构建仿真

    V-rep中显示激光扫描点  在VREP自带的场景中找到practicalPathPlanningDemo.ttt文件,删除场景中多余的物体只保留静态的地图.然后在Model browser→comp ...

  4. 对比几种在ROS中常用的几种SLAM算法

    在此因为要总结写一个文档,所以查阅资料,将总结的内容记录下来,欢迎大家指正! 文章将介绍使用的基于机器人操作系统(ROS)框架工作的SLAM算法. 在ROS中提供的五种基于2D激光的SLAM算法分别是 ...

  5. 将ROS中的/sensor_msgs/NavSatFix数据导入google earth显示轨迹

    将ros中的gps_msg数据导入google earth显示轨迹 [TOC] 1. 获取GPS数据 将ros中发布的gps topic输出到文本中 rostopic echo -p /gpsData ...

  6. 如何在ROS中使用PCL(2)

    记录关于我们运行roslaunch openni_launch openni.launch  命令时生成的话题以及这些话题的数据类型便于后期的处理,只有知道它们的数据结构,才能很好的对数据进行处理,我 ...

  7. 如何在ROS中使用PCL—数据格式(1)

    在ROS中点云的数据类型 在ROS中表示点云的数据结构有: sensor_msgs::PointCloud      sensor_msgs::PointCloud2     pcl::PointCl ...

  8. 在ROS中使用OpenCV

    1.在工作空间下创建程序包 $ cd ~/catkin_ws/src$ catkin_create_pkg robot_vision roscpp std_msgs cv_bridge image_t ...

  9. ROS中的日志(log)消息

    学会使用日志(log)系统,做ROS大型项目的主治医生 通过显示进程的运行状态是好的习惯,但需要确定这样做不会影响到软件的运行效率和输出的清晰度.ROS 日志 (log) 系统的功能就是让进程生成一些 ...

随机推荐

  1. IT公司100题-12-求1+2+…+n

    问题描述: 求1+2+…+n,要求不能使用乘除法.for.while.if.else.switch.case等关键字以及条件判断语句(A?B:C).   分析: 利用类的静态变量实现: new一含有n ...

  2. EL表达式中获取list长度

    在jsp页面中不能通过${list.size}取列表长度,而是 <%@ taglib uri="http://java.sun.com/jsp/jstl/core" pref ...

  3. iOS 下如果存在UIScrollerView 使用UIScreenEdgePanGestureRecognizer实现侧滑效果失效的问题

    当你在使用UIScreenEdgePanGestureRecognizer手势实现侧滑的时候,如果后期你导航控制器push出的界面中包含UIScrollerView,这个时候你会发现,侧滑效果无法实现 ...

  4. MapReduce数据流(二)

    输入块(InputSplit):一个输入块描述了构成MapReduce程序中单个map任务的一个单元.把一个MapReduce程序应用到一个数据集上,即是指一个作业,会由几个(也可能几百个)任务组成. ...

  5. (转)SQLite数据库增删改查操作

    原文:http://www.cnblogs.com/linjiqin/archive/2011/05/26/2059182.html SQLite数据库增删改查操作 一.使用嵌入式关系型SQLite数 ...

  6. 集合set的使用

    将无序对象储存在集合中 集合是类似于数组的一组对象,只是其中包含的项目是无序的(而数组是有序的).您通过枚举集合中的对象,或者将过滤器或测试应用到集合,来随机访问集合中的对象(使用 anyObject ...

  7. hdu - 2083 - 简易版之最短距离

    找到中位数 , 根据对称性 , 当中位数需要两个数取中值的时候不需要取 , 只需要其中的任意一个数几个 例如四个数 1 , 2 , 3 , 4 . 这四个数 , 其中的 2 和 3 都可以 . 然后求 ...

  8. 爬虫再探实战(三)———爬取动态加载页面——selenium

    自学python爬虫也快半年了,在目前看来,我面临着三个待解决的爬虫技术方面的问题:动态加载,多线程并发抓取,模拟登陆.目前正在不断学习相关知识.下面简单写一下用selenium处理动态加载页面相关的 ...

  9. susy-Toolkit 之翻译

    Toolkit工具包 The Susy 2.0 toolkit is built around our shorthand syntax. Use the shorthand to control e ...

  10. HTTP Live Streaming直播(iOS直播)技术分析与实现

    前些日子,也是项目需要,花了一些时间研究了HTTP Live Streaming(HLS)技术,并实现了一个HLS编码器HLSLiveEncoder,当然,C++写的.其功能是采集摄像头与麦克风,实时 ...