From 805b2951ce0df6b8b1ad37bba6e2b46cb223d8f4 Mon Sep 17 00:00:00 2001 From: BrnBlrg Date: Thu, 22 Aug 2024 13:18:58 -0700 Subject: [PATCH] Add description of retrieving parameters (#23) Add description of retrieving parameters from other nodes in rclpy via services. --------- Co-authored-by: Michael Ferguson --- rclpy/parameters.md | 44 ++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 44 insertions(+) diff --git a/rclpy/parameters.md b/rclpy/parameters.md index a5fe838..842c549 100644 --- a/rclpy/parameters.md +++ b/rclpy/parameters.md @@ -67,3 +67,47 @@ class MyNode(Node): For an example of calling the set_parameters service, see [ROS Answers](https://answers.ros.org/question/308541/ros2-rclpy-set-parameter-example/) + +## Getting parameters from other nodes + +In ros2, this is done through a service call. For example, to get the `robot_description` parameter published by `robot_state_publisher`: + +```python +from rcl_interfaces.srv import GetParameters + +import rclpy +from rclpy.node import Node + +class GetParam(Node): + def __init__(self): + super().__init__('joint_command_publisher') + self.client = self.create_client(GetParameters, '/robot_state_publisher/get_parameters') + robot_description = self.get_robot_description() + + def get_robot_description(self): + request = GetParameters.Request() + request.names = ["robot_description"] + future = self.client.call_async(request) + rclpy.spin_until_future_complete(self, future) + if future.result() is not None: + self.get_logger().info(future.result().values[0].string_value ) + return future.result().values[0].string_value # Assuming the parameter is a string, adjust as necessary + else: + self.get_logger().error('Failed to call service') + return None + +def main(args=None): + rclpy.init(args=args) + node = GetParam() + + try: + rclpy.spin(node) + except KeyboardInterrupt: + pass + + node.destroy_node() + rclpy.shutdown() + +if __name__ == '__main__': + main() +```