在类中使用参数(Python)
目标: 使用Python创建并运行具有ROS参数的类。
教程级别: 初学者
任务
1 创建一个包
在一个新的终端中 源化你的 ROS 2 安装,这样 ros2
命令才能正常工作。
按照:ref:这些指示 创建名为``ros2_ws``的新工作空间。
请记住,包应该在“src”目录中创建,而不是工作区的根目录。进入“ros2_ws/src”并创建一个新的包:
ros2 pkg create --build-type ament_python python_parameters --dependencies rclpy
您的终端将返回一条消息,确认已创建名为``python_parameters``的软件包及其所有必要的文件和文件夹。
“--dependencies”参数将自动添加必要的依赖项行到“package.xml”和“CMakeLists.txt”中。
1.1 更新 package.xml
因为您在包创建过程中使用了“--dependencies”选项,所以无需手动添加依赖项到“package.xml”或“CMakeLists.txt”中。
同样,确保将描述、维护者电子邮件和姓名以及许可证信息添加到 package.xml
中。
<description>Python parameter tutorial</description>
<maintainer email="you@email.com">Your Name</maintainer>
<license>Apache License 2.0</license>
2 编写Python节点
在``ros2_ws/src/python_parameters/python_parameters``目录中,创建一个名为``python_parameters_node.py``的新文件,并将以下代码粘贴到其中:
import rclpy
import rclpy.node
class MinimalParam(rclpy.node.Node):
def __init__(self):
super().__init__('minimal_param_node')
self.declare_parameter('my_parameter', 'world')
self.timer = self.create_timer(1, self.timer_callback)
def timer_callback(self):
my_param = self.get_parameter('my_parameter').get_parameter_value().string_value
self.get_logger().info('Hello %s!' % my_param)
my_new_param = rclpy.parameter.Parameter(
'my_parameter',
rclpy.Parameter.Type.STRING,
'world'
)
all_new_parameters = [my_new_param]
self.set_parameters(all_new_parameters)
def main():
rclpy.init()
node = MinimalParam()
rclpy.spin(node)
if __name__ == '__main__':
main()
2.1 检查代码
顶部的``import``语句用于导入包依赖项。
下面的代码创建了类和构造函数。构造函数中的``self.declare_parameter('my_parameter', 'world')``一行创建了一个名为``my_parameter``的参数,并将其默认值设置为``world``。参数类型根据默认值推断,所以在这种情况下它将被设置为字符串类型。接下来,``timer``被初始化为1的周期,这会导致``timer_callback``函数每秒执行一次。
class MinimalParam(rclpy.node.Node):
def __init__(self):
super().__init__('minimal_param_node')
self.declare_parameter('my_parameter', 'world')
self.timer = self.create_timer(1, self.timer_callback)
timer_callback``函数的第一行从节点中获取参数``my_parameter
,并将其存储在``my_param``中。接下来,get_logger``函数确保事件被记录。然后,``set_parameters``函数将参数``my_parameter``设置回默认的字符串值``world
。如果用户在外部更改了参数,这样可以确保它始终被重置回原始值。
def timer_callback(self):
my_param = self.get_parameter('my_parameter').get_parameter_value().string_value
self.get_logger().info('Hello %s!' % my_param)
my_new_param = rclpy.parameter.Parameter(
'my_parameter',
rclpy.Parameter.Type.STRING,
'world'
)
all_new_parameters = [my_new_param]
self.set_parameters(all_new_parameters)
接下来是我们的``timer_callback``,紧接着是``main``函数。在这里,ROS 2被初始化,一个``MinimalParam``类的实例被构建,然后``rclpy.spin``开始处理来自节点的数据。
def main():
rclpy.init()
node = MinimalParam()
rclpy.spin(node)
if __name__ == '__main__':
main()
2.1.1(可选)添加 ParameterDescriptor。
可选地,您可以为参数设置一个描述符。描述符允许您指定参数的文本描述以及其约束条件,比如将其设置为只读、指定范围等。为了使其工作,``__init__``代码必须进行如下更改:
# ...
class MinimalParam(rclpy.node.Node):
def __init__(self):
super().__init__('minimal_param_node')
from rcl_interfaces.msg import ParameterDescriptor
my_parameter_descriptor = ParameterDescriptor(description='This parameter is mine!')
self.declare_parameter('my_parameter', 'world', my_parameter_descriptor)
self.timer = self.create_timer(1, self.timer_callback)
其余的代码保持不变。运行节点后,您可以运行``ros2 param describe /minimal_param_node my_parameter``来查看类型和描述。
2.2 添加入口点
打开``setup.py``文件。再次,将``maintainer``、maintainer_email
、``description``和``license``字段与您的``package.xml``相匹配:
maintainer='YourName',
maintainer_email='you@email.com',
description='Python parameter tutorial',
license='Apache License 2.0',
将以下行添加到``entry_points``字段的``console_scripts``括号内:
entry_points={
'console_scripts': [
'minimal_param_node = python_parameters.python_parameters_node:main',
],
},
不要忘记保存。
3. 构建和运行
在构建之前,最好在工作空间的根目录(ros2_ws
)中运行``rosdep``来检查是否缺少依赖项:
rosdep install -i --from-path src --rosdistro humble -y
rosdep 只能在 Linux 上运行,所以您可以跳过下一步。
rosdep 只能在 Linux 上运行,所以您可以跳过下一步。
返回到您的工作空间的根目录 ros2_ws
,并构建您的新包:
colcon build --packages-select python_parameters
colcon build --packages-select python_parameters
colcon build --merge-install --packages-select python_parameters
打开一个新的终端,导航到 ros2_ws
,并加载设置文件:
source install/setup.bash
. install/setup.bash
call install/setup.bat
现在运行节点:
ros2 run python_parameters minimal_param_node
终端应该每秒返回以下消息:
[INFO] [parameter_node]: Hello world!
现在您可以看到参数的默认值,但您希望能够自己设置它。有两种方法可以实现这一点。
3.1 通过控制台进行更改
这部分将使用你从:doc:`关于参数的教程<../Beginner-CLI-Tools/Understanding-ROS2-Parameters/Understanding-ROS2-Parameters>`中学到的知识,并将其应用到你刚刚创建的节点上。
确保节点正在运行:
ros2 run python_parameters minimal_param_node
在另一个终端中打开,再次从``ros2_ws``目录中加载设置文件,然后输入以下命令行:
ros2 param list
在那里,您将看到自定义参数``my_parameter``。要进行更改,只需在控制台中运行以下命令行:
ros2 param set /minimal_param_node my_parameter earth
如果你得到输出``Set parameter successful``,就表示运行成功。如果你查看另一个终端,你应该看到输出变为``[INFO] [minimal_param_node]: Hello earth!``
由于后续节点将参数重新设置为“world”,后续的输出将显示为“[INFO] [minimal_param_node]: Hello world!”
3.2 通过启动文件进行更改
您还可以在启动文件中设置参数,但首先需要添加一个启动目录。在“ros2_ws/src/python_parameters/”目录中,创建一个名为“launch”的新目录。在其中创建一个名为“python_parameters_launch.py”的新文件。
from launch import LaunchDescription
from launch_ros.actions import Node
def generate_launch_description():
return LaunchDescription([
Node(
package='python_parameters',
executable='minimal_param_node',
name='custom_minimal_param_node',
output='screen',
emulate_tty=True,
parameters=[
{'my_parameter': 'earth'}
]
)
])
在这里,您可以看到当我们启动节点“parameter_node”时,我们将“my_parameter”设置为“earth”。通过添加下面的两行代码,我们确保在控制台中打印输出。
output="screen",
emulate_tty=True,
现在打开“setup.py”文件。将“import”语句添加到文件的顶部,并将另一个新语句添加到“data_files”参数中以包括所有启动文件:
import os
from glob import glob
# ...
setup(
# ...
data_files=[
# ...
(os.path.join('share', package_name), glob('launch/*launch.[pxy][yma]*')),
]
)
打开一个控制台并导航到您的工作空间的根目录``ros2_ws``,然后构建您的新软件包:
colcon build --packages-select python_parameters
colcon build --packages-select python_parameters
colcon build --merge-install --packages-select python_parameters
然后在新的终端中加载设置文件:
source install/setup.bash
. install/setup.bash
call install/setup.bat
现在使用刚刚创建的启动文件运行节点:
ros2 launch python_parameters python_parameters_launch.py
终端应该每秒返回以下消息:
[INFO] [custom_minimal_param_node]: Hello earth!