瀏覽代碼

feat: 完成第15章教程一口气累死了,今天大年初二加油!

鱼香ROS 2 年之前
父節點
當前提交
f8f3582658
共有 28 個文件被更改,包括 607 次插入9 次删除
  1. 9 9
      docs/_sidebar.md
  2. 52 0
      docs/humble/chapt15/1.简易雷达原理介绍.md
  3. 二進制
      docs/humble/chapt15/1.简易雷达原理介绍/imgs/142337vxx1av3eox3en1n3.jpg
  4. 二進制
      docs/humble/chapt15/1.简易雷达原理介绍/imgs/image-20220429113619974.png
  5. 二進制
      docs/humble/chapt15/1.简易雷达原理介绍/imgs/image-20230123180643802.png
  6. 90 0
      docs/humble/chapt15/2.测量距离学会超声波传感器.md
  7. 二進制
      docs/humble/chapt15/2.测量距离学会超声波传感器/imgs/image-20230123182325277.png
  8. 二進制
      docs/humble/chapt15/2.测量距离学会超声波传感器/imgs/image-20230123183006024.png
  9. 二進制
      docs/humble/chapt15/2.测量距离学会超声波传感器/imgs/image-20230123183325678.png
  10. 二進制
      docs/humble/chapt15/2.测量距离学会超声波传感器/imgs/image-20230123191703562.png
  11. 91 0
      docs/humble/chapt15/3.控制舵机学会使用执行器.md
  12. 二進制
      docs/humble/chapt15/3.控制舵机学会使用执行器/imgs/image-20230123191322090.png
  13. 二進制
      docs/humble/chapt15/3.控制舵机学会使用执行器/imgs/image-20230123192506245.png
  14. 二進制
      docs/humble/chapt15/3.控制舵机学会使用执行器/imgs/image-20230123194243072.png
  15. 100 0
      docs/humble/chapt15/4.舵机+超声波循环扫描.md
  16. 二進制
      docs/humble/chapt15/4.舵机+超声波循环扫描/imgs/image-20230123195240805.png
  17. 二進制
      docs/humble/chapt15/4.舵机+超声波循环扫描/imgs/image-20230123195439029.png
  18. 二進制
      docs/humble/chapt15/4.舵机+超声波循环扫描/imgs/image-20230123195720226.png
  19. 242 0
      docs/humble/chapt15/5.可视化点云-雷达消息合成.md
  20. 二進制
      docs/humble/chapt15/5.可视化点云-雷达消息合成/imgs/image-20230123195847790.png
  21. 二進制
      docs/humble/chapt15/5.可视化点云-雷达消息合成/imgs/image-20230123201236924.png
  22. 二進制
      docs/humble/chapt15/5.可视化点云-雷达消息合成/imgs/image-20230123201255929.png
  23. 二進制
      docs/humble/chapt15/5.可视化点云-雷达消息合成/imgs/image-20230123201345640.png
  24. 二進制
      docs/humble/chapt15/5.可视化点云-雷达消息合成/imgs/image-20230123201619516.png
  25. 二進制
      docs/humble/chapt15/5.可视化点云-雷达消息合成/imgs/image-20230123202107548.png
  26. 23 0
      docs/humble/chapt15/章节导读.md
  27. 二進制
      docs/humble/chapt15/章节导读/imgs/O1CN01ovUYBj1cAzC0TvQyb_!!3163773561.png_400x400.jpg
  28. 二進制
      docs/humble/chapt15/章节导读/imgs/超声波扫描 00_00_03-.gif

+ 9 - 9
docs/_sidebar.md

@@ -228,7 +228,7 @@
     - 进阶篇-优化配置
       - 暂定
       <!-- - 使用Carto纯定位替换AMCL -->
-- (五)ROS2控制硬件篇(更新中)
+- (五)ROS2控制硬件篇
   - 第 13 章 嵌入式开发之从点灯开始
     - [章节导读](humble/chapt13/章节导读.md)
     - 基础篇-嵌入式开发介绍与环境搭建
@@ -264,15 +264,15 @@
       - [2.做个时钟-系统时间同步](humble/chapt14/advance/2.做个时钟-系统时间同步.md)
       - [3.无线通讯-了解传输原理](humble/chapt14/advance/3.无线通讯-了解传输原理.md)
       - [4.榨干性能-使用双核运行MicroROS](humble/chapt14/advance/4.榨干性能-使用双核运行MicroROS.md)
-  - 第 15 章 ROS2硬件实战(自制简易雷达)
-      - 1.简易雷达原理介绍
-      - 2.使用超声波测量距离
-      - 3.使用pwm控制舵机角度
-      - 4.实现循环扫描测量
-      - 5.ROS雷达消息合成与发布
+  - 第 15 章 ROS2硬件实战(自制简易雷达)](humble/chapt15/章节导读.md
+      - [章节导读](humble/chapt15/1.简易雷达原理介绍.md
+      - [1.简易雷达原理介绍](humble/chapt15/3.控制舵机学会使用执行器.md
+      - [2.使用超声波测量距离](humble/chapt15/2.测量距离学会超声波传感器.md
+      - [3.使用pwm控制舵机角度](humble/chapt15/3.控制舵机学会使用执行器.md
+      - [4.实现循环扫描测量](humble/chapt15/4.舵机+超声波循环扫描.md
+      - [5.ROS雷达消息合成与发布](humble/chapt15/5.可视化点云-雷达消息合成.md
 
-
-- (六)实体机器人搭建篇
+- (六)实体机器人搭建篇(更新中)
   - 第 16 章 实体机器人硬件搭建
     - 章节导读
     - 基础篇-硬件基础篇

+ 52 - 0
docs/humble/chapt15/1.简易雷达原理介绍.md

@@ -0,0 +1,52 @@
+# 1.简易雷达原理介绍
+
+你好,我是爱吃鱼香ROS的小鱼。在正式开始制作我们的简易雷达前,我们先了解下原理。
+
+我们所说的雷达是一种测距设备,比如FishBot上搭载的雷达就可以实现360度的旋转测距——测量指定角度前方障碍物的距离。
+
+所以要实现一个简易雷达,我们必须要有一个可以测量距离的传感器,一个可以指定角度的电机。
+
+
+
+## 一、测距传感器超声波
+
+百度百科介绍
+
+超声波传感器是将超声波信号转换成其它能量信号(通常是电信号)的传感器。超声波是[振动频率](https://baike.baidu.com/item/振动频率/8068137)高于20kHz的机械波。它具有频率高、波长短、绕射现象小,特别是方向性好、能够成为[射线](https://baike.baidu.com/item/射线/327964)而定向传播等特点。超声波对液体、固体的穿透本领很大,尤其是在阳光不透明的固体中。超声波碰到杂质或分界面会产生显著反射形成反射回波,碰到活动物体能产生[多普勒效应](https://baike.baidu.com/item/多普勒效应/115710)。超声波传感器广泛应用在工业、国防、生物医学等方面。
+
+接着看看长什么样子:
+
+![img](1.%E7%AE%80%E6%98%93%E9%9B%B7%E8%BE%BE%E5%8E%9F%E7%90%86%E4%BB%8B%E7%BB%8D/imgs/image-20220429113619974.png)
+
+便宜的就长这样子,一共两个头,一个头用于发送波,一个头接收波。
+
+那么超声波传感器原理是什么呢?
+
+```
+距离=(发送时间-接收时间)*速度/2
+```
+
+下一节我们将通过代码根据这一原理进行距离测量测试。
+
+## 二、常用执行器舵机
+
+舵机是可以根据指定角度进行旋转的特殊电机。
+
+![9克舵机及其拆解 - DF创客社区 - 分享创造的喜悦](1.%E7%AE%80%E6%98%93%E9%9B%B7%E8%BE%BE%E5%8E%9F%E7%90%86%E4%BB%8B%E7%BB%8D/imgs/142337vxx1av3eox3en1n3.jpg)
+
+其硬件结构如上图所示,当我们把角度信息发送到控制板时,控制板通过电位器测量出当前的角度,然后根据当前角度和目标角度的角度差控制电机旋转,直到角度差变的几乎为零。
+
+
+
+## 三、结构设计
+
+主控板依然使用MicroROS学习板,购买雷达套餐(购买链接:https://item.taobao.com/item.htm?id=695473143304)的小伙伴可以通过赠送的支架将超声波固定到舵机上,也可以自行用胶枪之类的固定。最终的结构示意图如下
+
+![image-20230123180643802](1.%E7%AE%80%E6%98%93%E9%9B%B7%E8%BE%BE%E5%8E%9F%E7%90%86%E4%BB%8B%E7%BB%8D/imgs/image-20230123180643802.png)
+
+
+
+
+
+
+

二進制
docs/humble/chapt15/1.简易雷达原理介绍/imgs/142337vxx1av3eox3en1n3.jpg


二進制
docs/humble/chapt15/1.简易雷达原理介绍/imgs/image-20220429113619974.png


二進制
docs/humble/chapt15/1.简易雷达原理介绍/imgs/image-20230123180643802.png


+ 90 - 0
docs/humble/chapt15/2.测量距离学会超声波传感器.md

@@ -0,0 +1,90 @@
+# 2.测量距离学会超声波传感器
+
+你好,我是爱吃鱼香ROS的小鱼。上一节简单的介绍了超声波传感器,但是没有介绍如何通过代码使用,本节我们尝试使用并封装超声波模块。
+
+我们使用的超声波模块一共有四个引脚,分别是
+
+- `TRIG` 即发送引脚,用于发送超声波
+- `ECHO 即接收引脚,用于接收反射回来的超声波`
+- `VCC` 电源接5V
+- `GND` 电源地
+
+## 一、新建工程
+
+新建`example18_sr04`
+
+![image-20230123182325277](2.%E6%B5%8B%E9%87%8F%E8%B7%9D%E7%A6%BB%E5%AD%A6%E4%BC%9A%E8%B6%85%E5%A3%B0%E6%B3%A2%E4%BC%A0%E6%84%9F%E5%99%A8/imgs/image-20230123182325277.png)
+
+
+
+## 二、编写代码
+
+带注释的代码如下
+
+```c++
+#include <Arduino.h>
+#define Trig 27 // 设定SR04连接的Arduino引脚
+#define Echo 21
+
+void setup()
+{
+  Serial.begin(115200);
+  pinMode(Trig, OUTPUT); // 初始化舵机和超声波
+  pinMode(Echo, INPUT);  // 要检测引脚上输入的脉冲宽度,需要先设置为输入状态
+}
+
+void loop()
+{
+  static double mtime;
+  digitalWrite(Trig, LOW); // 测量距离
+  delayMicroseconds(2);    // 延时2us
+  digitalWrite(Trig, HIGH); 
+  delayMicroseconds(10); // 产生一个10us的高脉冲去触发SR04
+  digitalWrite(Trig, LOW);
+  mtime = pulseIn(Echo, HIGH);                  // 检测脉冲宽度,注意返回值是微秒us
+  float detect_distance = mtime / 58.0 / 100.0; // 计算出距离,输出的距离的单位是厘米cm
+  Serial.printf("distance=%f\n", detect_distance);
+  delay(500);
+}
+```
+
+## 三、代码注解
+
+核心代码分为两部分
+
+### 3.1发送超声
+
+方波产生,低-高-低
+
+![image-20230123183006024](2.%E6%B5%8B%E9%87%8F%E8%B7%9D%E7%A6%BB%E5%AD%A6%E4%BC%9A%E8%B6%85%E5%A3%B0%E6%B3%A2%E4%BC%A0%E6%84%9F%E5%99%A8/imgs/image-20230123183006024.png)
+
+```c++
+  digitalWrite(Trig, LOW); // 测量距离
+  delayMicroseconds(2);    // 延时2us
+  digitalWrite(Trig, HIGH); 
+  delayMicroseconds(10); // 产生一个10us的高脉冲去触发SR04
+  digitalWrite(Trig, LOW);
+```
+
+### 3.2 检测回响计算距离
+
+```c++
+mtime = pulseIn(Echo, HIGH);                  // 检测脉冲宽度,注意返回值是微秒us
+float detect_distance = mtime / 58.0 / 100.0; // 计算出距离,输出的距离的单位是米m
+```
+
+58是一个时间系数,根据声音在空气中传播速度计算而来。`pulseIn`函数用于检测某个引脚从当前时间跳变到高电平之间持续的时间。
+
+## 四、下载测试
+
+将超声波模块连接到开发板上的超声波接口上
+
+![image-20230123191703562](2.%E6%B5%8B%E9%87%8F%E8%B7%9D%E7%A6%BB%E5%AD%A6%E4%BC%9A%E8%B6%85%E5%A3%B0%E6%B3%A2%E4%BC%A0%E6%84%9F%E5%99%A8/imgs/image-20230123191703562.png)
+
+下载代码,打开串口,查看距离不断变化
+
+![image-20230123183325678](2.%E6%B5%8B%E9%87%8F%E8%B7%9D%E7%A6%BB%E5%AD%A6%E4%BC%9A%E8%B6%85%E5%A3%B0%E6%B3%A2%E4%BC%A0%E6%84%9F%E5%99%A8/imgs/image-20230123183325678.png)
+
+## 五、总结
+
+本节我们成功实现使用超声波实现距离测量功能,下一节我们尝试使用第三方库驱动舵机。

二進制
docs/humble/chapt15/2.测量距离学会超声波传感器/imgs/image-20230123182325277.png


二進制
docs/humble/chapt15/2.测量距离学会超声波传感器/imgs/image-20230123183006024.png


二進制
docs/humble/chapt15/2.测量距离学会超声波传感器/imgs/image-20230123183325678.png


二進制
docs/humble/chapt15/2.测量距离学会超声波传感器/imgs/image-20230123191703562.png


+ 91 - 0
docs/humble/chapt15/3.控制舵机学会使用执行器.md

@@ -0,0 +1,91 @@
+# 3.控制舵机学会使用执行器
+
+你好,我是爱吃鱼香ROS的小鱼。本节我们尝试使用第三方库来驱动舵机,实现让舵机指针指向任意角度。
+
+## 一、新建工程
+
+新建`example19_servo`
+
+![image-20230123191322090](3.%E6%8E%A7%E5%88%B6%E8%88%B5%E6%9C%BA%E5%AD%A6%E4%BC%9A%E4%BD%BF%E7%94%A8%E6%89%A7%E8%A1%8C%E5%99%A8/imgs/image-20230123191322090.png)
+
+在`platformio.ini`中添加舵机库
+
+```c++
+; PlatformIO Project Configuration File
+;
+;   Build options: build flags, source filter
+;   Upload options: custom upload port, speed and extra flags
+;   Library options: dependencies, extra library storages
+;   Advanced options: extra scripting
+;
+; Please visit documentation for the other options and examples
+; https://docs.platformio.org/page/projectconf.html
+
+[env:featheresp32]
+platform = espressif32
+board = featheresp32
+framework = arduino
+lib_deps = 
+    madhephaestus/ESP32Servo@^0.12.0
+```
+
+## 二、编写代码
+
+带注释代码如下。
+
+```c++
+#include <Arduino.h>
+#include <ESP32Servo.h>
+
+Servo servo1; // 创建对象
+
+void setup()
+{
+  servo1.setPeriodHertz(50);   // 舵机控制周期为50hz,即一个周期1000/50=20ms
+  servo1.attach(4, 500, 2500); // 使用GPIO4作为舵机1信号引脚,占空比为500-2500us即 0.5-2.5ms
+  servo1.write(90.0);          // 设置90度
+}
+
+void loop()
+{
+  for (int i = 0; i < int(180); i++)
+  {
+    servo1.write(i); // 设置角度
+    delay(5);
+  }
+}
+```
+
+
+
+## 三、代码注解
+
+这里主要需要介绍的是关于舵机的控制周期及占空比是如何设置的,这里设计到了PWM相关的知识。
+
+PWM即脉宽调制(Pulse-width Modulation, PWM),之前在I2C介绍章节中,小鱼曾介绍过通信时SCL上就是一个固定周期的脉冲
+
+![image-20230123192506245](3.%E6%8E%A7%E5%88%B6%E8%88%B5%E6%9C%BA%E5%AD%A6%E4%BC%9A%E4%BD%BF%E7%94%A8%E6%89%A7%E8%A1%8C%E5%99%A8/imgs/image-20230123192506245.png)
+
+PWM有两个重要的参数,第一个是周期,就像是正弦波,其周期就是2pi,指的是多久循环一次,我们这里设置的是50HZ,也就是说20ms。
+
+在一个周期里,引脚高电平的时间就称为占空比,这里我们设置的是0.5ms-2.5ms之间作为舵机控制的占空比范围。
+
+换句话说,假设我们设置当前舵机角度为90度,此时占空比
+
+```
+占空比 = 500+90*(2500-500)/180
+```
+
+
+
+## 四、下载测试
+
+将舵机插在S1接口,注意黄色线接蓝色信号。
+
+![image-20230123194243072](3.%E6%8E%A7%E5%88%B6%E8%88%B5%E6%9C%BA%E5%AD%A6%E4%BC%9A%E4%BD%BF%E7%94%A8%E6%89%A7%E8%A1%8C%E5%99%A8/imgs/image-20230123194243072.png)
+
+接着下载代码,观察舵机。
+
+## 五、总结
+
+本节我们通过三方库完成了对舵机的控制,下一节我们正式将舵机和超声波结合起来,测量指定角度下的距离。

二進制
docs/humble/chapt15/3.控制舵机学会使用执行器/imgs/image-20230123191322090.png


二進制
docs/humble/chapt15/3.控制舵机学会使用执行器/imgs/image-20230123192506245.png


二進制
docs/humble/chapt15/3.控制舵机学会使用执行器/imgs/image-20230123194243072.png


+ 100 - 0
docs/humble/chapt15/4.舵机+超声波循环扫描.md

@@ -0,0 +1,100 @@
+# 4.舵机+超声波循环扫描
+
+你好,我是爱吃鱼香ROS的小鱼。本节我们尝试将超声波的舵机结合起来实现循环扫描功能。
+
+## 一、新建工程
+
+新建`example20_simple_laser`
+
+![image-20230123195240805](4.%E8%88%B5%E6%9C%BA+%E8%B6%85%E5%A3%B0%E6%B3%A2%E5%BE%AA%E7%8E%AF%E6%89%AB%E6%8F%8F/imgs/image-20230123195240805.png)
+
+添加依赖,这里顺便吧microros的添加上,下一节直接使用
+
+```c++
+; PlatformIO Project Configuration File
+;
+;   Build options: build flags, source filter
+;   Upload options: custom upload port, speed and extra flags
+;   Library options: dependencies, extra library storages
+;   Advanced options: extra scripting
+;
+; Please visit documentation for the other options and examples
+; https://docs.platformio.org/page/projectconf.html
+
+[env:featheresp32]
+platform = espressif32
+board = featheresp32
+framework = arduino
+board_microros_transport = wifi
+lib_deps = 
+    https://gitee.com/ohhuo/micro_ros_platformio.git
+    madhephaestus/ESP32Servo@^0.12.0
+```
+
+## 二、编写代码
+
+原理是先控制舵机走到某个角度,接着调用超声波测量距离,这里小鱼将超声波测距离封装了一个函数,并用一个数组存储10个历史数据。
+
+```c++
+#include <Arduino.h>
+#include <micro_ros_platformio.h>
+#include <WiFi.h>
+#include <ESP32Servo.h>
+
+
+#define Trig 27 // 设定SR04连接的Arduino引脚
+#define Echo 21
+
+Servo servo1;
+
+float get_distance(int angle)
+{
+  static double mtime;
+  servo1.write(angle);     // 移动到指定角度
+  delay(25);               // 稳定身形
+  digitalWrite(Trig, LOW); // 测量距离
+  delayMicroseconds(2);
+  digitalWrite(Trig, HIGH);
+  delayMicroseconds(10); // 产生一个10us的高脉冲去触发SR04
+  digitalWrite(Trig, LOW);
+  mtime = pulseIn(Echo, HIGH);                  // 检测脉冲宽度,注意返回值是微秒us
+  float detect_distance = mtime / 58.0 / 100.0; // 计算出距离,输出的距离的单位是厘米cm
+  Serial.printf("point(%d,%f)\n", angle, detect_distance);
+  return detect_distance;
+}
+
+void setup()
+{
+  Serial.begin(115200);
+  pinMode(Trig, OUTPUT);     // 初始化舵机和超声波
+  pinMode(Echo, INPUT);      // 要检测引脚上输入的脉冲宽度,需要先设置为输入状态
+  servo1.setPeriodHertz(50); // Standard 50hz servo
+  servo1.attach(4, 500, 2500);
+  servo1.write(90.0);
+}
+
+void loop()
+{
+  for (int i = 0; i < 180; i++)
+  {
+    float distance = get_distance(i);
+    delay(10);
+  }
+}
+
+```
+
+
+
+## 三、下载测试
+
+连接好超声波和舵机。
+
+![image-20230123195439029](4.%E8%88%B5%E6%9C%BA+%E8%B6%85%E5%A3%B0%E6%B3%A2%E5%BE%AA%E7%8E%AF%E6%89%AB%E6%8F%8F/imgs/image-20230123195439029.png)
+
+下载代码,观察串口输出
+
+![image-20230123195720226](4.%E8%88%B5%E6%9C%BA+%E8%B6%85%E5%A3%B0%E6%B3%A2%E5%BE%AA%E7%8E%AF%E6%89%AB%E6%8F%8F/imgs/image-20230123195720226.png)
+
+这里显示的就是角度以及距离信息。
+

二進制
docs/humble/chapt15/4.舵机+超声波循环扫描/imgs/image-20230123195240805.png


二進制
docs/humble/chapt15/4.舵机+超声波循环扫描/imgs/image-20230123195439029.png


二進制
docs/humble/chapt15/4.舵机+超声波循环扫描/imgs/image-20230123195720226.png


+ 242 - 0
docs/humble/chapt15/5.可视化点云-雷达消息合成.md

@@ -0,0 +1,242 @@
+# 5.可视化点云-雷达消息合成
+
+你好,我是爱吃鱼香ROS的小鱼。上一节完成了指定角度距离的测量这一节我们将其合成ROS的laserscan消息,并将其通过microros发布到上位机,最终实现rviz2的可视化。
+
+![image-20230123195847790](5.%E5%8F%AF%E8%A7%86%E5%8C%96%E7%82%B9%E4%BA%91-%E9%9B%B7%E8%BE%BE%E6%B6%88%E6%81%AF%E5%90%88%E6%88%90/imgs/image-20230123195847790.png)
+
+
+
+## 一、雷达消息介绍
+
+使用指令`ros2 interface show sensor_msgs/msg/LaserScan`,可以看到ROS2对雷达数据接口的定义。
+
+```
+# Single scan from a planar laser range-finder
+#
+# If you have another ranging device with different behavior (e.g. a sonar
+# array), please find or create a different message, since applications
+# will make fairly laser-specific assumptions about this data
+
+std_msgs/Header header # timestamp in the header is the acquisition time of
+	builtin_interfaces/Time stamp
+		int32 sec
+		uint32 nanosec
+	string frame_id
+                             # the first ray in the scan.
+                             #
+                             # in frame frame_id, angles are measured around
+                             # the positive Z axis (counterclockwise, if Z is up)
+                             # with zero angle being forward along the x axis
+
+float32 angle_min            # start angle of the scan [rad]
+float32 angle_max            # end angle of the scan [rad]
+float32 angle_increment      # angular distance between measurements [rad]
+
+float32 time_increment       # time between measurements [seconds] - if your scanner
+                             # is moving, this will be used in interpolating position
+                             # of 3d points
+float32 scan_time            # time between scans [seconds]
+
+float32 range_min            # minimum range value [m]
+float32 range_max            # maximum range value [m]
+
+float32[] ranges             # range data [m]
+                             # (Note: values < range_min or > range_max should be discarded)
+float32[] intensities        # intensity data [device-specific units].  If your
+                             # device does not provide intensities, please leave
+                             # the array empty.
+```
+
+### 1.1 header部分
+
+头部分,主要是设置雷达的frame_id和时间戳,在microros中可以这样赋值
+
+```c++
+pub_msg.header.frame_id = micro_ros_string_utilities_set(pub_msg.header.frame_id, "laser"); // 初始化消息内容
+int64_t current_time = rmw_uros_epoch_millis();
+pub_msg.header.stamp.sec = current_time * 1e-3;
+pub_msg.header.stamp.nanosec = current_time - pub_msg.header.stamp.sec * 1000;
+```
+
+### 1.2 数据部分
+
+- angle_min 当前数据中最小的测量角度
+
+- angle_max 当前数据中最大的测量角度
+
+- angle_increment 我们默认就是一次1度,所以可以直接写
+
+  ```
+    pub_msg.angle_increment = 1.0 / 180 * PI;
+  ```
+
+- time_increment 每个数据之间递增的时间,可以直接使用扫描的总之间除点数
+- scan_time 扫描时间,开始扫描到结束扫描的时间
+- range_min 最小范围可以直接赋值 我们设置成`0.05`即5cm
+- range_max 最大范围,我们直接设置成5.0m
+
+- ranges 测量的距离值数组
+- intensities 测量的强度,这里我们直接忽略即可
+
+## 二、代码编写
+
+直接在上一节工程上修改,全部代码如下,一次我们发布10个点,并且启动了ESP32的双核,同时采取了时间同步,保证雷达数据的时间戳正常。
+
+```c++
+#include <Arduino.h>
+#include <micro_ros_platformio.h>
+#include <WiFi.h>
+#include <rcl/rcl.h>
+#include <rclc/rclc.h>
+#include <rclc/executor.h>
+#include <ESP32Servo.h>
+
+#include <sensor_msgs/msg/laser_scan.h>
+#include <micro_ros_utilities/string_utilities.h>
+
+#define PCOUNT 10
+#define Trig 27 // 设定SR04连接的Arduino引脚
+#define Echo 21
+
+rclc_executor_t executor;
+rclc_support_t support;
+rcl_allocator_t allocator;
+rcl_node_t node;
+
+rcl_publisher_t publisher;           // 声明话题发布者
+sensor_msgs__msg__LaserScan pub_msg; // 声明消息文件
+
+Servo servo1;
+bool connected_agent = false;
+
+void microros_task(void *param)
+{
+
+  IPAddress agent_ip;                                                    // 设置通过WIFI进行MicroROS通信
+  agent_ip.fromString("192.168.2.105");                                  // 从字符串获取IP地址
+  set_microros_wifi_transports("fishbot", "12345678", agent_ip, 8888);   // 设置wifi名称,密码,电脑IP,端口号
+  delay(2000);                                                           // 延时时一段时间,等待设置完成
+  allocator = rcl_get_default_allocator();                               // 初始化内存分配器
+  rclc_support_init(&support, 0, NULL, &allocator);                      // 创建初始化选项
+  rclc_node_init_default(&node, "example20_simple_laser", "", &support); // 创建节点
+  rclc_publisher_init_default(                                           // 发布初始化
+      &publisher,
+      &node,
+      ROSIDL_GET_MSG_TYPE_SUPPORT(sensor_msgs, msg, LaserScan),
+      "/scan");
+
+  rclc_executor_init(&executor, &support.context, 1, &allocator);                             // 创建执行器
+  pub_msg.header.frame_id = micro_ros_string_utilities_set(pub_msg.header.frame_id, "laser"); // 初始化消息内容
+  pub_msg.angle_increment = 1.0 / 180 * PI;
+  pub_msg.range_min = 0.05;
+  pub_msg.range_max = 5.0;
+
+  while (true)
+  {
+    delay(10);
+    if (!rmw_uros_epoch_synchronized()) // 判断时间是否同步
+    {
+      rmw_uros_sync_session(1000); //  同步时间
+      continue;
+    }
+    connected_agent = true;
+    rclc_executor_spin_some(&executor, RCL_MS_TO_NS(100)); // 循环处理数据
+  }
+}
+
+float get_distance(int angle)
+{
+  static double mtime;
+  servo1.write(angle);     // 移动到指定角度
+  delay(25);               // 稳定身形
+  digitalWrite(Trig, LOW); // 测量距离
+  delayMicroseconds(2);
+  digitalWrite(Trig, HIGH);
+  delayMicroseconds(10); // 产生一个10us的高脉冲去触发SR04
+  digitalWrite(Trig, LOW);
+  mtime = pulseIn(Echo, HIGH);                  // 检测脉冲宽度,注意返回值是微秒us
+  float detect_distance = mtime / 58.0 / 100.0; // 计算出距离,输出的距离的单位是厘米cm
+  Serial.printf("point(%d,%f)\n", angle, detect_distance);
+  return detect_distance;
+}
+
+void setup()
+{
+  Serial.begin(115200);
+  pinMode(Trig, OUTPUT);     // 初始化舵机和超声波
+  pinMode(Echo, INPUT);      // 要检测引脚上输入的脉冲宽度,需要先设置为输入状态
+  servo1.setPeriodHertz(50); // Standard 50hz servo
+  servo1.attach(4, 500, 2500);
+  servo1.write(90.0);
+  xTaskCreatePinnedToCore(microros_task, "microros_task", 10240, NULL, 1, NULL, 0);
+}
+
+void loop()
+{
+  if (!connected_agent)
+    return;
+
+  static float ranges[PCOUNT + 1];
+  for (int i = 0; i < int(180 / PCOUNT); i++)
+  {
+    int64_t start_scan_time = rmw_uros_epoch_millis();
+    for (int j = 0; j < PCOUNT; j++)
+    {
+      int angle = i * 10 + j;
+      ranges[j] = get_distance(angle);
+    }
+    pub_msg.angle_min = float(i * 10) / 180 * PI;       // 结束角度
+    pub_msg.angle_max = float(i * (10 + 1)) / 180 * PI; // 结束角度
+
+    int64_t current_time = rmw_uros_epoch_millis();
+    pub_msg.scan_time = float(current_time - start_scan_time) * 1e-3;
+    pub_msg.time_increment = pub_msg.scan_time / PCOUNT;
+    pub_msg.header.stamp.sec = current_time * 1e-3;
+    pub_msg.header.stamp.nanosec = current_time - pub_msg.header.stamp.sec * 1000;
+    pub_msg.ranges.data = ranges;
+    pub_msg.ranges.capacity = PCOUNT;
+    pub_msg.ranges.size = PCOUNT;
+    rcl_publish(&publisher, &pub_msg, NULL);
+    delay(10);
+  }
+}
+
+```
+
+
+
+## 三、下载测试
+
+下载代码
+
+![image-20230123201236924](5.%E5%8F%AF%E8%A7%86%E5%8C%96%E7%82%B9%E4%BA%91-%E9%9B%B7%E8%BE%BE%E6%B6%88%E6%81%AF%E5%90%88%E6%88%90/imgs/image-20230123201236924.png)
+
+启动agent。
+
+```shell
+docker run -it --rm -v /dev:/dev -v /dev/shm:/dev/shm --privileged --net=host microros/micro-ros-agent:$ROS_DISTRO udp4 --port 8888 -v6
+```
+
+![image-20230123201255929](5.%E5%8F%AF%E8%A7%86%E5%8C%96%E7%82%B9%E4%BA%91-%E9%9B%B7%E8%BE%BE%E6%B6%88%E6%81%AF%E5%90%88%E6%88%90/imgs/image-20230123201255929.png)
+
+测试
+
+```
+ros2 node list
+ros2 topic list
+ros2 topic echo /scan
+```
+
+![image-20230123201345640](5.%E5%8F%AF%E8%A7%86%E5%8C%96%E7%82%B9%E4%BA%91-%E9%9B%B7%E8%BE%BE%E6%B6%88%E6%81%AF%E5%90%88%E6%88%90/imgs/image-20230123201345640.png)
+
+接着打开终端,输入rviz2打开rviz
+
+![image-20230123201619516](5.%E5%8F%AF%E8%A7%86%E5%8C%96%E7%82%B9%E4%BA%91-%E9%9B%B7%E8%BE%BE%E6%B6%88%E6%81%AF%E5%90%88%E6%88%90/imgs/image-20230123201619516.png)
+
+修改配置,显示过去5s数据
+
+![image-20230123202107548](5.%E5%8F%AF%E8%A7%86%E5%8C%96%E7%82%B9%E4%BA%91-%E9%9B%B7%E8%BE%BE%E6%B6%88%E6%81%AF%E5%90%88%E6%88%90/imgs/image-20230123202107548.png)
+
+## 四、总结
+
+本节我们成功实现了使用超声波和舵机模拟雷达数据,并将其合成scan发布到电脑上使用rviz2进行可视化。至此我们完成了ROS2硬件控制的所有课程。下面迎接你的将是移动机器人和机械臂开发课程,请做好准备,继续出发。

二進制
docs/humble/chapt15/5.可视化点云-雷达消息合成/imgs/image-20230123195847790.png


二進制
docs/humble/chapt15/5.可视化点云-雷达消息合成/imgs/image-20230123201236924.png


二進制
docs/humble/chapt15/5.可视化点云-雷达消息合成/imgs/image-20230123201255929.png


二進制
docs/humble/chapt15/5.可视化点云-雷达消息合成/imgs/image-20230123201345640.png


二進制
docs/humble/chapt15/5.可视化点云-雷达消息合成/imgs/image-20230123201619516.png


二進制
docs/humble/chapt15/5.可视化点云-雷达消息合成/imgs/image-20230123202107548.png


+ 23 - 0
docs/humble/chapt15/章节导读.md

@@ -0,0 +1,23 @@
+# 第 15 章 ROS2硬件实战(自制简易雷达)
+
+你好,我是小鱼。本章是ROS2硬件实战教程的实践章节,我们将通过自制一个简易雷达同时学习使用传感器、执行器和MicroROS。
+
+最终效果如下:
+
+![超声波扫描 00_00_03-](%E7%AB%A0%E8%8A%82%E5%AF%BC%E8%AF%BB/imgs/%E8%B6%85%E5%A3%B0%E6%B3%A2%E6%89%AB%E6%8F%8F%2000_00_03-.gif)
+
+> 上图中,主控板、超声波、舵机及支架 板可以在小鱼的店铺直接购买,性价比接地气,直达链接:[https://item.taobao.com/item.htm?id=695473143304](https://item.taobao.com/item.htm?id=695473143304)。
+>
+> ![](%E7%AB%A0%E8%8A%82%E5%AF%BC%E8%AF%BB/imgs/O1CN01ovUYBj1cAzC0TvQyb_!!3163773561.png_400x400.jpg)
+
+
+
+--------------
+
+技术交流&&问题求助:
+
+- **微信公众号及交流群:鱼香ROS**
+- **小鱼微信:AiIotRobot**
+- **QQ交流群:139707339**
+
+- 版权保护:已加入“维权骑士”(rightknights.com)的版权保护计划

二進制
docs/humble/chapt15/章节导读/imgs/O1CN01ovUYBj1cAzC0TvQyb_!!3163773561.png_400x400.jpg


二進制
docs/humble/chapt15/章节导读/imgs/超声波扫描 00_00_03-.gif