Parameters

In this exercise, we will look at ROS Parameters for configuring nodes

Motivation

By this point in these tutorials (or your career), you’ve probably typed the words int main(int argc, char** argv) more times than you can count. The arguments to main are the means by which a system outside scope and understanding of your program can configure your program to do a particular task. These are command line parameters.

The ROS ecosystem has an analogous system for configuring nodes. It’s a key-value storage model that is associated with each node individually. It’s best used to pass configuration parameters to nodes at run-time (e.g. to identify which camera a node should subscribe to), but it can be used for much more complicated items.

Reference Example

Using Parameters

Further Information and Resource

Understanding ROS2 parameters

Scan-N-Plan Application: Problem Statement

In previous exercises, we added a service with the following definition:

# request
string base_frame
---
# response
geometry_msgs/Pose pose
bool success

So far we haven’t used the request field, base_frame, for anything. In this exercise we’ll use ROS parameters to set this field. You will need to:

  1. Declare inside the class that the Node uses a base_frame parameter of string type.

  2. Load the parameter base_frame and store it in a local string object.

    • If no parameter is provided, default to the parameter to "world".

  3. When making the service call to the vision_node, use this parameter to fill out the Request::base_frame field.

  4. Add a parameters arguments to your launch file to initialize the new value.

Scan-N-Plan Application: Guidance

  1. Open up myworkcell_node.cpp for editing.

  2. Inside the ScanNPlan class constructor, add a call to declare_parameter:

    this->declare_parameter("base_frame", "world");
    
    • The first argument is the parameter name, the second is the default value if the parameter is not set.

    • The parameter type is fixed from the type of the default value. You may safely assume any value you get when accessing the base_frame parameter is a string.

  3. In the main function, after creating the node but before calling start, create a temporary string object, std::string base_frame;, and then use get_parameter to load the parameter "base_frame".

    std::string base_frame = app->get_parameter("base_frame").as_string();
    
    • The declare_parameter function actually returns the parameter value as well, so if you want to declare and get a parameter in the same place, you can do it with one line.

  4. Also prior to calling start, insert a call to sleep for a few seconds. Without this, the service will be called immediately when the node starts and if the nodes all start together, there is a good chance the vision_node won’t have received any data from the fake_ar_publisher yet:

    //Wait for the vision node to receive data
    rclcpp::sleep_for(std::chrono::seconds(2));
    
  5. Add an argument to your myworkcell_node “start” function of a string named base_frame, and assign the value from the argument into the service request. Make sure to update the app->start call in your main() routine to pass through the base_frame value you obtained.

    void start(const std::string& base_frame)
    {
      ...
      request->base_frame = base_frame;
      RCLCPP_INFO_STREAM(get_logger(), "Requesting pose in base frame: " << base_frame);
      ...
    }
    
    int main(...)
    {
      ...
      app->start(base_frame);
      ...
    }
    
  6. Now we’ll add myworkcell_node to the existing workcell.launch.py file, so we can set the base_frame parameter from a launch file. We’d like the vision_node to return the position of the target relative to the world frame, for motion-planning purposes. Even though that’s the default value, we’ll specify it in the launch-file anyway:

    launch_ros.actions.Node(
        name='myworkcell_node',
        package='myworkcell_core',
        executable='myworkcell_node',
        output='screen',
        parameters=[{'base_frame': 'world'}],
    )
    
    • Note that the parameters arguments provides the names and values to use as a list of dictionaries.

  7. Try it out by re-building and running the system.

    ros2 launch myworkcell_support workcell.launch.py
    
    • Press Ctrl+C to kill the running nodes

    • Edit the launch file to change the base_frame parameter value (e.g. to “test2”)

    • Re-launch workcell.launch.py, and observe that the “request frame” has changed

      • If you didn’t build with the --symlink-install option, you will need to re-build after editing the launch file, to copy the updates into the “install” directory.

      • The response frame doesn’t change, because we haven’t updated vision_node (yet) to handle the request frame. Vision_node always returns the same frame (for now).

    • Set the base_frame back to “world”

Challenge Exercise

  • Imagine a human is cooporating with the robot in this scenario. Try adding a new parameter for the human-operational frame.