简介:参数也是ROS2系统中很重要的一项功能,主要是用来对节点进行配置,一般用在调试过程中,通过命令行的方式修改节点的一些配置,用以辅助调试,另外节点参数也支持导入和导出,调试好的参数可以导出到本地保存,再次启动时可以加载调试好的参数直接使用。


目录

1、问题描述

2、解决思路

3、编码实现

4、命令行操作示例


1、问题描述

       小车自动行驶时,需要对道路进行识别,在虚拟仿真环境中,道路有以下几种元素:

  • 黑色的地面
  • 白色边线
  • 黄色的道路分割线
  • 红色的路口停车线

        行驶过程中,需要通过对以上元素相对位置的观察来估算小车的位姿,再进一步就可以给出控制指令让小车按照既定规则行驶。在这个过程中,我们识别道路元素主要还是通过颜色来判断,但是有一个问题是无论仿真环境还是真实环境,某一个颜色一般都是指一个颜色范围,并不是一个固定值,尤其是在真实环境下,由于光照的影响,颜色的范围浮动会更大,所以如何准确的设定道路元素的颜色范围就是一个必须要解决的问题,传统的解决方式就是经验+实践,接下来我们通过学习ROS2的参数来解决道路元素颜色范围求解的问题。

2、解决思路

        简介中提到,参数一般是用来对节点进行配置的,所以我们根据要求解的配置项来定义参数,因为我们要识别白色、黄色、红色,RGB颜色模型不好界定颜色的范围,一般使用HSV颜色模型:

  • 色调H:用角度度量,opencv中取值范围为0-180,从红色开始按逆时针方向计算,红色为0,绿色为60,蓝色为120,180与0相同还是红色,所以红色会有两段;
  • 饱和度S:饱和度S表示颜色接近光谱色的程度。opencv中取值范围为0-255,值越大,颜色越饱和,也就是颜色越鲜艳;
  • 明度V:明度表示颜色明亮的程度,opencv取值范围为0(黑)到255(白);
            根据颜色模型,我们预设以下参数:

参数名

功能

white_h_low,white_s_low,white_v_low

白色范围下限

white_h_high,white_s_high,white_v_high

白色范围上限

yellow_h_low,yellow_s_low,yellow_v_low

黄色范围下限

yellow_h_high,yellow_s_high,yellow_v_high

黄色范围上限

red_h_low,red_s_low,red_v_low

红色范围下限,red_h_low指低于180的段,对应上限为180

red_h_high,red_s_high,red_v_high

红色范围上限,red_h_high指大于0的段,对应下限为0

color_select

要实现单色调试,预设颜色选择参数

        然后在软件中设定颜色选择功能,指定识别颜色,根据颜色取值范围识别相关颜色并显示区域,与原图做对比,观察识别结果是否准确,不准确的情况下,通过命令行修改颜色取值范围进行调试,直到识别结果准确为止,最后保存调试好的参数。

        附opencv中颜色取值范围表,表中数据可供参考,做为基础值,在基础值基础上进行调整,可以快速调试出结果。

3、编码实现

        创建新的功能包,要订阅图像主题,直接添加依赖项sensor_msgs:

$ cd ~/ros2_ws/src
$ ros2 pkg create line_detect --build-type ament_python --node-name line_detect_node --dependencies rclpy sensor_msgs

编辑源码文件line_detect_node.py

#!/usr/bin/env python3
 
import rclpy
from rclpy.node import Node
 
import cv2
import numpy as np
 
from sensor_msgs.msg import Image
from cv_bridge import CvBridge
 
class LineDetectNode(Node):
    
    def __init__(self, name):
        super().__init__(name)
        
        self.color_select = 'white'                  #指定调试颜色,white、yellow、red
        self.white_lower = np.array([0,0,0])         #白色颜色分量下限
        self.white_higher = np.array([180,255,255])  #白色颜色分量上限
        self.yellow_lower = np.array([0,0,0])        #黄色颜色分量下限
        self.yellow_higher = np.array([180,255,255]) #黄色颜色分量上限
        self.red_lower = np.array([0,0,0])           #红色颜色分量下限(H分量0以上)
        self.red_higher = np.array([90,255,255])     #红色颜色分量上限(H分量0以上)
        self.red_lower1 = np.array([90,0,0])         #红色颜色分量下限(H分量180以下)
        self.red_higher1 = np.array([180,255,255])   #红色颜色分量上限(H分量180以下)
        
        self.declare_parameter('color_select', 'white') #定义调试颜色选择参数
        #分别定义白色颜色分量参数,按照标准参考,下限[0,0,221],上限[180,30,255]
        self.declare_parameter('white_h_low', 0)
        self.declare_parameter('white_s_low', 0)
        self.declare_parameter('white_v_low', 221)
        self.declare_parameter('white_h_high', 180)
        self.declare_parameter('white_s_high', 30)
        self.declare_parameter('white_v_high', 255)
        #分别定义黄色颜色分量参数,按照标准参考,下限[26,43,46],上限[34,255,255]
        self.declare_parameter('yellow_h_low', 26)
        self.declare_parameter('yellow_s_low', 43)
        self.declare_parameter('yellow_v_low', 46)
        self.declare_parameter('yellow_h_high', 34)
        self.declare_parameter('yellow_s_high', 255)
        self.declare_parameter('yellow_v_high', 255)
        #分别定义红色颜色分量参数,按照标准参考分两段:
        #下限[156,43,46],上限[180,255,255]
        #下限[0,43,46],上限[10,255,255]
        self.declare_parameter('red_h_low', 156)
        self.declare_parameter('red_s_low', 43)
        self.declare_parameter('red_v_low', 46)
        self.declare_parameter('red_h_high', 10)
        self.declare_parameter('red_s_high', 255)
        self.declare_parameter('red_v_high', 255)
        
        self.bridge = CvBridge()
        #订阅图像主题
        self.sub_img = self.create_subscription(Image, 'duckiebot_node/image', self.cb_img, 10)
        #启动参数更新定时器,每一秒更新一次,从参数中取值赋值到变量中
        self.timer = self.create_timer(1, self.update_parameters)
    
    #图像主题订阅回调函数
    def cb_img(self, imgmsg):
        #转化图像格式
        image = self.bridge.imgmsg_to_cv2(imgmsg, 'bgr8')
        #根据当前颜色设定,从图像中截取指定颜色区域
        color_image = self.get_color(image, self.color_select)
        #原图与截取图像横向合并显示
        images = np.concatenate([image, color_image], axis=1)
        cv2.imshow('images', images)
        cv2.waitKey(1)
    #图像截取函数,image是原图,color是要截取的颜色    
    def get_color(self, image, color):
        if color=='white':
            return self.get_white(image)
        elif color=='yellow':
            return self.get_yellow(image)
        elif color=='red':
            return self.get_red(image)
        else:
            return image
    
    #截取白色
    def get_white(self, image):
        #转为HSV颜色模型
        hsv = cv2.cvtColor(image, cv2.COLOR_BGR2HSV)
        #根据设定范围取符合颜色范围的二值图像
        white_mask = cv2.inRange(hsv, self.white_lower, self.white_higher)
        #图像按位运算,截取白色区域
        white_area = cv2.bitwise_and(image, image, mask=white_mask)
        return white_area
    
    #截取黄色
    def get_yellow(self, image):
        #转为HSV颜色模型
        hsv = cv2.cvtColor(image, cv2.COLOR_BGR2HSV) 
        #根据设定范围取符合颜色范围的二值图像
        yellow_mask = cv2.inRange(hsv, self.yellow_lower, self.yellow_higher)
        #图像按位运算,截取黄色区域
        yellow_area = cv2.bitwise_and(image, image, mask=yellow_mask)
        return yellow_area
    #截取红色
    def get_red(self, image):
        hsv = cv2.cvtColor(image, cv2.COLOR_BGR2HSV) 
        #根据设定范围取符合颜色范围的二值图像,红色有两段,需要合并两段
        red_mask = cv2.inRange(hsv, self.red_lower, self.red_higher)
        red_mask |= cv2.inRange(hsv, self.red_lower1, self.red_higher1)
        #图像按位运算,截取红色区域
        red_area = cv2.bitwise_and(image, image, mask=red_mask)
        return red_area
    #参数更新函数,在定时器中调用,从参数中获取数值赋值到颜色分量设置中
    def update_parameters(self):
        #字符型参数取值
        self.color_select = self.get_parameter('color_select').get_parameter_value().string_value
        #整形参数取值,调用封装函数
        self.white_lower = np.array([self.get_integer_value('white_h_low'),self.get_integer_value('white_s_low'),self.get_integer_value('white_v_low')])
        self.white_higher = np.array([self.get_integer_value('white_h_high'),self.get_integer_value('white_s_high'),self.get_integer_value('white_v_high')])
        self.yellow_lower = np.array([self.get_integer_value('yellow_h_low'),self.get_integer_value('yellow_s_low'),self.get_integer_value('yellow_v_low')])
        self.yellow_higher = np.array([self.get_integer_value('yellow_h_high'),self.get_integer_value('yellow_s_high'),self.get_integer_value('yellow_v_high')])
        self.red_lower = np.array([0,self.get_integer_value('red_s_low'),self.get_integer_value('red_v_low')])
        self.red_higher = np.array([self.get_integer_value('red_h_high'),self.get_integer_value('red_s_high'),self.get_integer_value('red_v_high')])
        self.red_lower1 = np.array([self.get_integer_value('red_h_low'),self.get_integer_value('red_s_low'),self.get_integer_value('red_v_low')])
        self.red_higher1 = np.array([180,self.get_integer_value('red_s_high'),self.get_integer_value('red_v_high')])
    #为了简化代码,封装一下从参数中取整型value的函数
    def get_integer_value(self, param_name):
        value = self.get_parameter(param_name).get_parameter_value().integer_value
        return value
 
def main(args=None):
    rclpy.init(args=args)
    node = LineDetectNode(name="line_detect_node")
    rclpy.spin(node=node)
    rclpy.shutdown()
 
 
if __name__ == '__main__':
    main()

返回工作空间,编译、配置环境变量并运行duckiebot节点和新节点:

$ cd ~/ros2_ws
$ colcon build --packages-select line_detect
$ source install/setup.bash
$ ros2 run line_detect line_detect_node

开新终端

$ source ~/ros2_ws/install/setup.bash
$ ros2 run duckiebot duckiebot_node

        默认是在截取白色,可以看到默认配置下,白色截取很不理想,接下来我们通过学习命令行参数设置来实现颜色截取的调试。

4、命令行操作示例

        上文我们已经启动了两个节点,通过命令行操作需要再开启一个终端,并设置环境变量,然后使用列表指令查看系统中的现有参数:

$ source ~/ros2_ws/install/setup.bash
$ ros2 param list

      可以看到我们在line_detect_node中设定的一系列参数,可以以通过get和set命令获取和设置指定参数:

$ ros2 param get /line_detect_node color_select

$ ros2 param get /line_detect_node white_h_low

   get指令可以查看当前参数的值和类型。

        利用set指令可以改变指定参数的值,上文提到,默认参数白色识别不理想,我们可以再看看黄色和红色的情况:

$ ros2 param set /line_detect_node color_select "yellow"
$ ros2 param set /line_detect_node color_select "red"
$ ros2 param set /line_detect_node color_select "white"

        设置颜色截取为黄色,如果图像中有黄色区域,机会被截取显示出来,根据下图可见,效果还可以,同样也可以查看红色区域,可以配合键盘控制节点,控制小车行走到不同区域查看颜色截取效果。

    因为白色区域截取不理想,把color_select修改回white,改变白色颜色分量参数值:

#降低白色明度下限
$ ros2 param set /line_detect_node white_v_low 100
#提高白色饱和度上限
$ ros2 param set /line_detect_node white_s_high 50

        效果如下图,比默认设定好很多:

    利用同样的方式,可以依次调试黄色和红色,设定较为合适的颜色分量值。

        调整完之后,需要保存设定的参数,否则关闭重启后设置还原:

        命令格式:ros2 param dump <node_name> --output-dir <保存路径>

$ ros2 param dump /line_detect_node --output-dir ~/ros2_ws/src/line_detect/line_detect/

        将参数保存到与源码文件相同目录,文件名称与节点名称一致,文件为yaml格式,保存后内容如下:

/line_detect_node:
  ros__parameters:
    color_select: white
    red_h_high: 10
    red_h_low: 156
    red_s_high: 255
    red_s_low: 43
    red_v_high: 255
    red_v_low: 46
    use_sim_time: false
    white_h_high: 180
    white_h_low: 0
    white_s_high: 50
    white_s_low: 0
    white_v_high: 255
    white_v_low: 100
    yellow_h_high: 34
    yellow_h_low: 26
    yellow_s_high: 255
    yellow_s_low: 43
    yellow_v_high: 255
    yellow_v_low: 46

  节点再次启动时,可以加载之前保存的参数:

        命令格式:ros2 run <package_name> <node_name> --ros-args --params-file <file_path>

$ ros2 run line_detect line_detect_node --ros-args --params-file src/line_detect/line_detect/line_detect_node.yaml

     加载已有参数文件,可以将配置恢复到上次保存时的状态。