How to create ros2 parameters?

the last task of the rosject for the course is to call an action client node this way:

ros2 run nav2_project go_to_pose --ros-args --params-file spot-list.yaml -p spot_name:=corner1

I’ve tried to search it and I tried many codes but I wasn’t able to do it correctly, this topic is neither covered in this course material nor in the prerequisites

Hi @Hegazi ,

The basic way to create parameters for a ROS2 node will be as follows:

# this is a yaml document - this line can be removed #
ros2_node_name: # this is the name of your ros2 program's node
  ros__parameters: # this is a necessary line - it has 2 underscores
    param1: value # direct parameter
    param2: value # direct parameter
    param3: # parameter with sub-parameters
      param3param1: value # sub-parameter
      param3param2: value # sub-parameter

You need to make sure that this yaml config file is called in your launch program when the node starts.

Once the node has started and the parameters file is loaded, You can then do:
ros2 param list on a terminal. You should then see the following in your output:

. # other ros2 nodes
/your_ros2_node_name:
  param1
  param2
  param3
. # other ros2 nodes

Let me know if this helped you and/or if you need more assistance.

Regards,
Girish

1 Like

I’ve created a .yaml file contains 3 spots

and an action client code to choose one a spot from the yaml file to navigate to it using slam
by passing ros arguments in terminal like this:

the client node code:

import rclpy
from rclpy.action import ActionClient
from rclpy.node import Node
from nav2_msgs.action import NavigateToPose
from geometry_msgs.msg import PoseStamped

class MoveToSpot(Node):
    def __init__(self):
        super().__init__("move_to_pose")
        self.client = ActionClient(
            self,
            NavigateToPose,
            '/navigate_to_pose'
        )
        
    def send_goal(self, x, y, z, yaw):

        goal = NavigateToPose.Goal()
        pose = PoseStamped()
        pose.header.frame_id = 'map'
        pose.pose.position.x = x
        pose.pose.position.y = y
        pose.pose.position.z = z
        pose.pose.orientation.w = yaw
        goal.pose = pose
        
        self.client.wait_for_server()
        self._send_goal_future = self.client.send_goal_async(goal, feedback_callback=self.feedback_callback)
        self._send_goal_future.add_done_callback(self.goal_response_callback)

    def goal_response_callback(self, future):
        goal_handle = future.result()
        if not goal_handle.accepted:
            self.get_logger().info('Goal rejected :(')
            return

        self.get_logger().info('Goal accepted :)')

        self._get_result_future = goal_handle.get_result_async()
        self._get_result_future.add_done_callback(self.get_result_callback)

    def get_result_callback(self, future):
        result = future.result().result
        rclpy.shutdown()

    def feedback_callback(self, feedback_msg):
        feedback = feedback_msg.feedback
        self.get_logger().info(
            'Received feedback: {0}, {1}, {2}'.format(feedback.current_pose.pose.position.x, feedback.current_pose.pose.position.y, feedback.current_pose.pose.orientation.w))
    
def main(args=None):
    rclpy.init(args=None)
    node = MoveToSpot()
    node.send_goal()
    rclpy.spin(node)


if __name__ == '__main__':
    main()

how to modify my code to call the client from terminal as in picture?

Hi @Hegazi ,

To pass ROS2 arguments to a program and access them, you need to add two lines for each of the parameter.

So, in your program go_to_pose, inside the __init__ function, you need to add the following lines:

self.declare_parameter(name="your-param-name")
self.param = self.get_parameter(name="your-param-name").value

# so the lines for "params-file" and "spot-name" will be
self.declare_parameter(name="params-file")
self.params_file = self.get_parameter(name="params-file").value
self.declare_parameter(name="spot-name")
self.spot_name = self.get_parameter(name="spot-name").value

Add these lines after calling the super class, that is, after the line super().__init__("node_name").

I hope this helps. Let me know if you need more clarity.

Regards,
Girish

This topic was automatically closed 5 days after the last reply. New replies are no longer allowed.