首页 > 其他分享 >ros2 - microros - 雷达 -可视化点云

ros2 - microros - 雷达 -可视化点云

时间:2024-07-01 20:58:15浏览次数:14  
标签:angle header scan pub msg microros time 点云 ros2

上一节完成了指定角度距离的测量这一节我们将其合成ROS的laserscan消息,并将其通过microros发布到上位机,最终实现rviz2的可视化。

 一、雷达消息介绍
使用指令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中可以这样赋值

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的双核,同时采取了时间同步,保证雷达数据的时间戳正常。

#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);
  }
}

三、下载测试
下载代码

 启动agent。

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

 测试

ros2 node list
ros2 topic list
ros2 topic echo /scan

 接着打开终端,输入rviz2打开rviz

 修改配置,显示过去5s数据

 四、总结
本节我们成功实现了使用超声波和舵机模拟雷达数据,并将其合成scan发布到电脑上使用rviz2进行可视化。至此我们完成了ROS2硬件控制的所有课程。下面迎接你的将是移动机器人和机械臂开发课程,请做好准备,继续出发。

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;

标签:angle,header,scan,pub,msg,microros,time,点云,ros2
From: https://www.cnblogs.com/ai-ldj/p/18278839

相关文章

  • Open3D Ransac点云配准算法(粗配准)
    目录一、概述1.1简介1.2RANSAC在点云粗配准中的应用步骤二、代码实现2.1关键函数2.2完整代码2.3代码解析2.3.1计算FPFH1.法线估计2.计算FPFH特征2.3.2全局配准1.函数:execute_global_registration2.距离阈值3.registration_ransac_based_on_feature_matching函......
  • Open3D 点云快速全局配准FGR算法(粗配准)
    目录一、概述1.1原理和步骤1.2关键技术和优势1.3应用场景二、代码实现2.1关键代码2.1.1.函数:execute_fast_global_registration2.1.2调用registration_fgr_based_on_feature_matching函数2.2完整代码三、实现效果3.1原始点云3.2粗配准后点云一、概述    ......
  • Open3D 点云的旋转与平移
    目录一、概述1.1旋转1.2平移二、代码实现2.1实现旋转2.2实现平移2.3组合变换三、实现效果3.1原始点云3.2变换后点云一、概述        在Open3D中,点云的旋转和平移是通过几何变换来实现的。几何变换可以应用于点云对象,使其在空间中移动或旋转到新的位置和......
  • ros microros 舵机控制原理
    1.什么是舵机:舵机是一种位置伺服的驱动器,主要是由外壳、电路板、驱动马达、齿轮组和位置反馈电位计等元件所构成,适用于那些需要角度不断变化并可以保持的控制系统。2.舵机的工作原理是:控制电路板接收来自信号线的控制信号,控制电机转动,电机带动一系列齿轮组,减速后传动至输出舵......
  • ROS2创建简单的C++功能包
    1.创建功能包终端下,进入ws00_helloworld/src目录,使用如下指令创建一个C++功能包:ros2pkgcreatepkg01_helloworld_cpp--build-typeament_cmake--dependenciesrclcpp--node-namehelloworld执行完毕,在src目录下将生成一个名为pkg01_helloworld_cpp的目录,且目录中已经......
  • ros microros 使用超声波雷达测量距离
    我们使用的超声波模块一共有四个引脚,分别是TRIG即发送引脚,用于发送超声波ECHO即接收引脚,用于接收反射回来的超声波VCC电源接5VGND电源地一、新建工程新建example18_sr04二、编写代码带注释的代码如下#include<Arduino.h>#defineTrig27//设定SR04连接的Arduino引脚......
  • ros mocroros 使用双核运行microros
    在硬件篇开始的第一节时,曾提到,我们所使用的开发板单片机是双核240M主频的,但是在后面的开发中我们并没有真正的使用了双核,主频也是使用的默认160MHZ。所以本节带你一起带你一起提升主频并启动双核进行MicoROS的双核。一、双核与RTOS介绍 所谓双核指的是ESP32单片机有两个内核,所......
  • 使用 ROS2的多机器人探索
    原文链接:https://www.youtube.com/watch?v=J0RZP_xJ3XA ThisvideoshowsademonstrationoftheSOSproject,dedicatedtoforestfiredetectionusingafleetofrobots.Severalimportantissuesareaddressed.这段视频展示了SOS项目的演示,该项目致力于使用机器人......
  • lidar3607.2 雷达点云数据处理软件功能介绍
    V7.2.220240511获取软件安装包联系邮箱:[email protected],资源源于网络,本介绍用于学习使用,如有侵权请您联系删除!1.平台修复对不包含枝下高特征的单木进行枝下高提取时,生成的treedb枝下高字段产生异常记录,查看属性表时软件崩溃的问题;2.林业修复使用treedb作为种子点进行......
  • 点云处理中阶 RangeImages
    目录一、什么是深度图1、深度图的特点与生成二、深度图的应用1、深度图的应用三、深度图前沿应用四、PCL中定义的RangeImage1、从点云创建深度图从深度图中提取边界四、资料补充1、什么是莫尔条纹法莫尔条纹法的原理莫尔条纹法的应用莫尔条纹法的优势和局限优势......