ros2-rolling 参数服务通信
每个 ROS 2 节点都会自动创建以下服务:
-
/your_node_name/set_parameters -
/your_node_name/get_parameters
参数变更流程
-
客户端节点调用
set_parameters服务 -
服务器(目标)节点接收参数变更请求
-
在服务器(目标)节点,触发注册的
param_change_callback -
在服务器(目标)节点,回调函数验证参数:
-
如果有效:接受变更并返回成功
-
如果无效:拒绝变更并返回原因
-
-
在服务器(目标)节点,响应返回给客户端节点
参数类型处理
在参数客户端的节点中,在 Python 中需要显式指定参数类型
def _create_parameter_value(self, value): param_value = ParameterValue() if isinstance(value, float): param_value.type = ParameterValue.Type.DOUBLE param_value.double_value = value # ... 其他类型处理
验证机制
在参数服务的节点中,回调中实现业务逻辑验证:
if param.name == 'speed': if param.value < 0: result.successful = False result.reason = "速度不能为负值"
参数服务通信 举例1
服务器
1 #!/usr/bin/env python3 2 import rclpy 3 from rclpy.node import Node 4 from rcl_interfaces.msg import SetParametersResult 5 from rclpy.parameter import Parameter 6 7 class ParamNode(Node): 8 def __init__(self): 9 super().__init__('param_node')# 节点名称,即参数服务器时使用。 10 11 # 声明参数 12 self.declare_parameter('speed', 1.0) 13 self.declare_parameter('color', 'blue') 14 self.declare_parameter('enable', True) 15 16 # 添加参数变更回调 17 self.add_on_set_parameters_callback(self.param_change_callback) 18 19 self.get_logger().info("参数节点已启动,等待参数修改...") 20 21 def param_change_callback(self, params): 22 """处理参数变更的回调函数""" 23 result = SetParametersResult(successful=True) 24 25 for param in params: 26 # 记录参数变更 27 self.get_logger().info( 28 f"参数变更: {param.name} = {param.value} (类型: {type(param.value).__name__})" 29 ) 30 31 # 参数验证逻辑 32 if param.name == 'speed': 33 if param.value < 0: 34 result.successful = False 35 result.reason = "速度不能为负值" 36 elif param.value > 10: 37 self.get_logger().warn("警告:速度超过安全阈值!") 38 39 elif param.name == 'color': 40 valid_colors = ['red', 'green', 'blue', 'yellow'] 41 if param.value not in valid_colors: 42 result.successful = False 43 result.reason = f"无效颜色,必须是 {', '.join(valid_colors)}" 44 45 elif param.name == 'enable': 46 # 当enable参数变化时执行特定操作 47 if param.value: 48 self.get_logger().info("系统已启用") 49 else: 50 self.get_logger().warn("系统已禁用") 51 52 return result 53 54 def main(args=None): 55 rclpy.init(args=args) 56 node = ParamNode() 57 try: 58 rclpy.spin(node) 59 except KeyboardInterrupt: 60 pass 61 finally: 62 node.destroy_node() 63 rclpy.shutdown() 64 65 if __name__ == '__main__': 66 main()
客户端
1 #!/usr/bin/env python3 2 import rclpy 3 from rclpy.node import Node 4 from rcl_interfaces.srv import SetParameters 5 from rcl_interfaces.msg import Parameter, ParameterValue, ParameterType 6 import time 7 8 class ParamClient(Node): 9 def __init__(self): 10 super().__init__('param_client') 11 self.target_node = 'param_node' # 目标节点名称,即参数服务器 12 13 # 创建参数服务客户端 14 self.client = self.create_client( 15 SetParameters, 16 f'/{self.target_node}/set_parameters' 17 ) 18 19 # 等待服务可用 20 while not self.client.wait_for_service(timeout_sec=1.0): 21 self.get_logger().info('等待参数服务...') 22 23 # 修改目标节点参数 24 self.modify_parameters() 25 26 def modify_parameters(self): 27 """修改目标节点参数序列""" 28 # 1. 修改速度参数 29 self.set_param('speed', 2.5) 30 time.sleep(1) 31 32 # 2. 修改颜色参数 33 self.set_param('color', 'green') 34 time.sleep(1) 35 36 # 3. 尝试设置无效速度 37 self.set_param('speed', -1.0) 38 time.sleep(1) 39 40 # 4. 尝试设置无效颜色 41 self.set_param('color', 'purple') 42 time.sleep(1) 43 44 # 5. 切换启用状态 45 self.set_param('enable', False) 46 47 def set_param(self, name, value): 48 """设置单个参数""" 49 param = Parameter() 50 param.name = name 51 param.value = self._create_parameter_value(value) 52 53 request = SetParameters.Request() 54 request.parameters = [param] 55 56 self.get_logger().info(f"尝试设置 {name} = {value}...") 57 58 future = self.client.call_async(request) 59 future.add_done_callback( 60 lambda future: self.param_set_callback(future, name, value)) 61 62 def _create_parameter_value(self, value): 63 """根据Python类型创建ParameterValue""" 64 param_value = ParameterValue() 65 66 if isinstance(value, float): 67 param_value.type = ParameterType.PARAMETER_DOUBLE 68 param_value.double_value = value 69 elif isinstance(value, bool): 70 param_value.type = ParameterType.PARAMETER_BOOL 71 param_value.bool_value = value 72 elif isinstance(value, int): 73 param_value.type = ParameterType.PARAMETER_INTEGER 74 param_value.integer_value = value 75 elif isinstance(value, str): 76 param_value.type = ParameterType.PARAMETER_STRING 77 param_value.string_value = value 78 79 else: 80 raise ValueError(f"不支持的参数类型: {type(value)}") 81 82 return param_value 83 84 def param_set_callback(self, future, name, value): 85 """处理参数设置响应""" 86 try: 87 response = future.result() 88 if response.results[0].successful: 89 self.get_logger().info(f"✓ 成功设置 {name} = {value}") 90 else: 91 self.get_logger().error( 92 f"✗ 设置失败: {name} = {value} - 原因: {response.results[0].reason}" 93 ) 94 except Exception as e: 95 self.get_logger().error(f"服务调用失败: {str(e)}") 96 97 def main(args=None): 98 rclpy.init(args=args) 99 client = ParamClient() 100 rclpy.spin(client) 101 client.destroy_node() 102 rclpy.shutdown() 103 104 if __name__ == '__main__': 105 main()
参数服务通信 举例2
客户端
1 #!/usr/bin/env python3 2 import rclpy 3 from rclpy.node import Node 4 from rcl_interfaces.srv import GetParameters, SetParameters 5 from rcl_interfaces.msg import Parameter, ParameterValue, ParameterType 6 import asyncio 7 from typing import List, Union, Optional 8 9 class ParameterClient(Node): 10 def __init__(self): 11 super().__init__('parameter_client')#节点名称 12 self.counter = 0 13 14 # 创建服务客户端 15 self.get_param_cli = self.create_client( 16 GetParameters, # 服务接口 17 'usr_get_parameters' # 服务名称 18 ) 19 self.set_param_cli = self.create_client( 20 SetParameters, # 服务接口 srv_type 21 'usr_set_parameters' # 服务名称 svr_name 22 ) 23 24 # 服务可用性检查 25 self._check_services_timer = self.create_timer(1.0, self._check_services) # 周期1.0s , 回调函数 26 self._services_ready = False 27 28 def _check_services(self) -> None: 29 """检查服务可用性""" 30 if not self._services_ready: 31 if self.get_param_cli.service_is_ready() and self.set_param_cli.service_is_ready(): 32 self._services_ready = True 33 self._check_services_timer.cancel() 34 self.get_logger().info("✅ 参数服务已就绪") 35 self.timer = self.create_timer(3.0, self._timer_callback) 36 else: 37 self.get_logger().info('等待参数服务...', throttle_duration_sec=5) 38 39 def _timer_callback(self) -> None: #在 Python 中,->符号是类型提示(Type Hints)的一部分,用于指定函数的返回类型 40 """定时器回调(同步触发异步操作)""" # 定时器同步触发 41 self.counter += 1 42 asyncio.create_task(self._demo_parameter_ops())# 异步操作 43 44 async def _demo_parameter_ops(self) -> None: #在 Python 中,->符号是类型提示(Type Hints)的一部分,用于指定函数的返回类型 45 """异步参数操作演示""" 46 try: 47 # 获取参数 48 names = ['robot_speed','operation_mode'] # 参数名称 表 49 values = await self._get_parameters(names) # 调方法,按名取得参数值 50 51 if values: 52 self.get_logger().info( 53 f"当前参数: speed={values[0].double_value}, mode={values[1].string_value}" #按序取得参数值 54 ) 55 56 # 设置新参数 57 new_speed = 1.0 + (self.counter % 3) * 0.5 58 success = await self._set_parameter('robot_speed', new_speed) #异步操作,向服务器发请求和键值对,设置新值 59 60 if success: 61 self.get_logger().info(f"✅ 成功设置速度: {new_speed}") 62 else: 63 self.get_logger().error("❌ 参数设置失败") 64 65 except Exception as e: 66 self.get_logger().error(f"操作异常: {str(e)}", throttle_duration_sec=10) 67 68 async def _get_parameters(self, names: List[str]) -> Optional[List[ParameterValue]]: 69 """获取参数(带重试机制)""" 70 req = GetParameters.Request() # 请求实例 71 req.names = names # 请求实例,参数名称表 72 73 for attempt in range(3): # 最大重试3次 74 try: 75 future = self.get_param_cli.call_async(req) # 异步操作 实例 76 await asyncio.wait_for(future, timeout=2.0) # 阻塞,等待完成 77 return future.result().values # 返回 参数名称表对应的参数值表 78 except asyncio.TimeoutError: 79 self.get_logger().warn(f"获取参数超时 (尝试 {attempt + 1}/3)") 80 except Exception as e: 81 self.get_logger().warn(f"获取参数失败: {str(e)} (尝试 {attempt + 1}/3)") 82 83 await asyncio.sleep(1.0) # 重试前等待 1.0秒 84 85 self.get_logger().error(f"无法获取参数: {names}") 86 return None # 返回,空 87 88 async def _set_parameter( 89 self, 90 name: str, 91 value: Union[float, str, int, bool] 92 ) -> bool: 93 """设置单个参数""" 94 param = Parameter() 95 param.name = name 96 97 if isinstance(value, float): 98 param.value.type = ParameterType.PARAMETER_DOUBLE 99 param.value.double_value = value 100 elif isinstance(value, str): 101 param.value.type = ParameterType.PARAMETER_STRING 102 param.value.string_value = value 103 elif isinstance(value, int): 104 param.value.type = ParameterType.PARAMETER_INTEGER 105 param.value.integer_value = value 106 elif isinstance(value, bool): 107 param.value.type = ParameterType.PARAMETER_BOOL 108 param.value.bool_value = value 109 else: 110 raise TypeError(f"不支持的参数类型: {type(value)}") 111 112 req = SetParameters.Request() 113 req.parameters = [param] # 参数名称-值 表 114 115 try: 116 future = self.set_param_cli.call_async(req) 117 await asyncio.wait_for(future, timeout=2.0) 118 return future.result().results[0].successful 119 except asyncio.TimeoutError: 120 self.get_logger().error("设置参数超时") 121 return False 122 except Exception as e: 123 self.get_logger().error(f"设置参数失败: {str(e)}") 124 return False 125 126 def main(args=None): 127 rclpy.init(args=args) 128 node = ParameterClient() 129 130 try: 131 # 使用单线程执行器 132 executor = rclpy.executors.SingleThreadedExecutor() 133 executor.add_node(node) 134 135 # 创建新的事件循环 136 loop = asyncio.new_event_loop() 137 asyncio.set_event_loop(loop) 138 139 async def spin(): 140 while rclpy.ok(): 141 executor.spin_once(timeout_sec=0.1) 142 await asyncio.sleep(0.1) # 让出控制权 143 144 loop.run_until_complete(spin())#事件循环 145 146 except KeyboardInterrupt: 147 node.get_logger().info("关闭节点...") 148 except Exception as e: 149 node.get_logger().error(f"节点异常: {str(e)}") 150 finally: 151 node.destroy_node() 152 rclpy.shutdown() 153 # 清理事件循环 loop.close() 154 155 if __name__ == '__main__': 156 main()
服务器
# export RCUTILS_CONSOLE_OUTPUT_FORMAT =[{function_name}:{line_number}:{message}]
# echo "export RCUTILS_CONSOLE_OUTPUT_FORMAT='[{file_name}:{line_number}:{name}] {message}'" >> ~/.bashrc
# pakage.xml 中的依赖项 <depend>rclpy</depend>
1 #!/usr/bin/env python3 2 import rclpy 3 from rclpy.node import Node 4 from rcl_interfaces.srv import GetParameters, SetParameters 5 from rcl_interfaces.msg import Parameter, ParameterValue, ParameterType, SetParametersResult 6 from rclpy.parameter import Parameter as Param 7 # export RCUTILS_CONSOLE_OUTPUT_FORMAT =[{function_name}:{line_number}:{message}] 8 #echo "export RCUTILS_CONSOLE_OUTPUT_FORMAT='[{file_name}:{line_number}:{name}] {message}'" >> ~/.bashrc 9 class ParameterServer(Node): 10 def __init__(self): 11 super().__init__('parameter_server') 12 13 # 声明可共享的参数 14 self.declare_parameter('robot_speed', 1.0) 15 self.declare_parameter('operation_mode', 'normal')#operation_mode 16 self.declare_parameter('battery_level', 95) 17 18 # 提供参数服务 19 self.get_srv = self.create_service( 20 GetParameters, 21 'usr_get_parameters', 22 self.handle_get_params 23 ) 24 25 self.set_srv = self.create_service( 26 SetParameters, 27 'usr_set_parameters', 28 self.handle_set_params 29 ) 30 31 self.get_logger().info("🟢 参数服务已启动") 32 33 def handle_get_params(self, request, response): 34 """处理参数查询请求""" 35 response.values = [] 36 for name in request.names: 37 self.get_logger().info(f"参数名: {name}") 38 if self.has_parameter(name): 39 param = self.get_parameter(name) # 在节点内,按参数名取得变量值 40 p_value = ParameterValue() # 参数对象实例 41 42 # 根据参数类型填充值 43 if param.type_ == Param.Type.DOUBLE: 44 p_value.double_value = param.value # 参数变量,赋值 45 p_value.type = ParameterType.PARAMETER_DOUBLE 46 elif param.type_ == Param.Type.STRING: 47 p_value.string_value = param.value # 参数变量,赋值 48 p_value.type = ParameterType.PARAMETER_STRING 49 elif param.type_ == Param.Type.INTEGER: 50 p_value.integer_value = param.value # 参数变量,赋值 51 p_value.type = ParameterType.PARAMETER_INTEGER 52 53 response.values.append(p_value) # 参数变量,赋值 54 self.get_logger().info(f"已知参数: {name}:{p_value}") 55 else: 56 self.get_logger().info(f"未知参数: {name}") 57 response.values.append(ParameterValue()) # 加入参数的值 58 59 return response # 返回 60 61 def handle_set_params(self, request, response): 62 """处理参数设置请求""" 63 results = [] 64 for param in request.parameters: #参数名称-值 表 65 try: 66 # 参数验证逻辑 67 if param.name == 'robot_speed' and param.value.double_value < 0: 68 raise ValueError("速度不能为负值") 69 70 # 更新参数 71 self.set_parameters([Param.from_parameter_msg(param)]) # 重新设置参数名-值 72 results.append(True) 73 self.get_logger().info(f"更新参数: {param.name}={param.value}") 74 except Exception as e: 75 self.get_logger().error(f"参数设置失败: {str(e)}") 76 results.append(False) 77 78 response.results = [SetParametersResult(successful=r) for r in results] # 服务应答 79 return response 80 81 def main(args=None): 82 rclpy.init(args=args) 83 node = ParameterServer() 84 rclpy.spin(node) 85 node.destroy_node() 86 rclpy.shutdown() 87 88 if __name__ == '__main__': 89 main()

浙公网安备 33010602011771号