ros2学习(05)—利用参数控制骰子点数

Published: less than 1 minute read, with 171 words. Post views:

ros2学习日志(5)—利用参数控制骰子点数

3.0 写在前面

前面我们创建了一个掷骰子游戏1.0,利用服务实现了player与god的交互。

但是,在程序中,我们使用了随机数random.randint(1,6)来模拟骰子的点数,这一点很不爽。

那么,我们能不能控制骰子的点数呢?

答案当然是肯定的,这里需要使用到参数。

3.1 参数的实现

参数的实现与发布、订阅、服务等类似,在节点中声明一个参数即可;

3.1.1 新建god_service_with_param.py

在god/god文件夹内,建立god_service_with_param.py文件,并写入以下代码:(仅仅是对之前的代码进行了稍微修改)

import rclpy #导入ros的客户端库,必备步骤
from rclpy.node import Node #rclpy.node是ros客户端库自带的Node类,用于创建节点
import random #python自带的随机数库
from interfaces.srv import DiceGameService #导入自定义的服务接口,interfaces是package的名称
                                           # .srv是指srv文件夹下

class GodServiceNodeWithParam(Node):  #采用面向对象(OOP)的方式建立node; 定义了一个GodServiceNodeWithParam的类,继承rclpy.node中的Node;
    def __init__(self,name):  #定义初始化方法;或者叫构造函数。。(构造函数是个人的理解,源自C++)
        super().__init__(name) #调用父类初始化,需要传入参数name,通常name是实例化的Node的名称,即节点名字;比如本例子中节点名字是 God
        self.get_logger().info("GodServiceNodeWithParam初始化成功!")  #get_logger().info是rclpy.node中的方法;   
        self.create_service(DiceGameService,"diceGameServiceWithParam",self.diceGame_callback)
        self.declare_parameter("diceNum",0) 
        # declara_parameter声明参数
        # 第一个参数是参数名字,是字符串类型,我们这里定义参数名称是diceNum
        # 第二个参数是参数的数值,我们使用0
       
    def diceGame_callback(self,request,response): #掷骰子服务回调函数
        #request 客户端请求对象,携带着来自客户端的数据。这这里我们收到的应该是一个int32的数据
        #response 服务端响应,返回服务端的处理结果;我们返回布尔数据类型
        #返回值:response
        if request.input_num == self.get_parameter("diceNum").get_parameter_value().integer_value:  
            #判断从player收到的数字是不是参数diceNum中的数值
        	#self.get_parameter("diceNum")是获取参数
        	#.get_parameter_value()是获取参数的值
        	#.integer_value是获取整型数值
            response.guess_result= True   #如果猜正确,输出结果
        else:
            response.guess_result= False  #如果猜错误,也输出结果
        return response
        
def main(args=None):  #main函数,程序执行的主入口
    rclpy.init(args=args)  # 初始化客户端库,必备步骤
    node=GodServiceNodeWithParam("diceGameServiceGodWithParam")  # 新建节点对象,必备步骤;传入参数,将Node实例化
    rclpy.spin(node)   # spin循环节点,保持节点运行,检测是否收到退出指令(Ctrl+C),必备步骤
    rclpy.shutdown()  # 关闭客户端库,必备步骤
  • declara_parameter是声明参数的意思,注意不是之前常见的create_命令
  • 获取参数的数值命令比较长,需要用到3步
    • 1.get_parameter(“diceNum”)先获取参数
    • 2.get_parameter_value()获取参数的值
    • 3.integer_value获取值的类型

3.1.2 修改setup.py

修改setup.py,添加新的入口点,并取名为diceGameServiceWithParam,注意这个名字就是编译后的节点名称。

image-20220413102827119

3.3 编译运行查看参数

依次colcon build, source install/setup.bash之后,运行服务端节点:

ros2 run god diceGameServiceWithParam

image-20220413103041045

使用ros2 param list命令查看参数列表:

image-20220413103317037

可以看到我们创建的diceNum参数已经出现了。

我们在创建参数的时候,给diceNum的值是0,如何查看呢?

使用ros2 param get /diceGameServiceGodWithParam diceNum获取parameter的值:

/diceGameServiceGodWithParam是节点名称;

diceNum是参数名称;

image-20220413103705514

可以看到参数的数值是0

3.4 参数的手动设置

3.4.1 ros2 param set参数设置

我们想要控制骰子的点数,那么必然要有手段对参数的数值进人为修改;

使用ros2 param set /diceGameServiceGodWithParam diceNum 5修改parameter的值:

/diceGameServiceGodWithParam是节点名称;

diceNum是参数名称;

5是设置的数值;注意空格

image-20220413104324489

显示设置参数成功

  • 使用set只是在当前的会话中把参数修改了,并不是永久修改参数。

3.4.2 ros2 param dump参数保存

使用ros2 param dump /diceGameServiceGodWithParam将设置的参数保存,保存到一个yaml文件中

image-20220413104725120

打开yaml文件,可以看到diceNum及其数值

image-20220413104826183

3.4.3 加载参数文件

在ros2 run一个节点的时候加载参数文件,便可以直接修改节点中的参数

使用ros2 run god diceGameServiceWithParam --ros-args --params-file diceGameServiceGodWithParam.yaml运行节点并加载参数文件

  • –ros-args–params-file是ros2 run命令的可选参数,后面跟咱们参数文件的名字,可以直接加载参数文件并运行节点

image-20220413105603351

使用ros2 param get /diceGameServiceGodWithParam diceNum查看当前参数的数值:

image-20220413105746218

可以看到diceNum的值从默认的0修改为了5.

至此,完成了手动控制骰子点数。


Tags: ,

Categories:

Comments