{"id":1987,"date":"2020-06-22T09:13:17","date_gmt":"2020-06-22T09:13:17","guid":{"rendered":"https:\/\/roboticsbackend.com\/?p=1987"},"modified":"2023-04-27T12:30:53","modified_gmt":"2023-04-27T12:30:53","slug":"rclcpp-params-tutorial-get-set-ros2-params-with-cpp","status":"publish","type":"post","link":"https:\/\/roboticsbackend.com\/rclcpp-params-tutorial-get-set-ros2-params-with-cpp\/","title":{"rendered":"rclcpp Params Tutorial &#8211; Get and Set ROS2 Params with Cpp"},"content":{"rendered":"<p>In this rclcpp params tutorial you&#8217;ll see how to get and set ROS2 params with rclcpp, in a Cpp node.<\/p>\n<p>If you want to do the same with Python, check out the <a href=\"https:\/\/roboticsbackend.com\/rclpy-params-tutorial-get-set-ros2-params-with-python\/\">rclpy tutorial<\/a>.<\/p>\n<div id=\"ez-toc-container\" class=\"ez-toc-v2_0_81 counter-hierarchy ez-toc-counter ez-toc-grey ez-toc-container-direction\">\n<p class=\"ez-toc-title\" style=\"cursor:inherit\">Table of Contents<\/p>\n<label for=\"ez-toc-cssicon-toggle-item-69fc897cf371a\" class=\"ez-toc-cssicon-toggle-label\"><span class=\"\"><span class=\"eztoc-hide\" style=\"display:none;\">Toggle<\/span><span class=\"ez-toc-icon-toggle-span\"><svg style=\"fill: #999;color:#999\" xmlns=\"http:\/\/www.w3.org\/2000\/svg\" class=\"list-377408\" width=\"20px\" height=\"20px\" viewBox=\"0 0 24 24\" fill=\"none\"><path d=\"M6 6H4v2h2V6zm14 0H8v2h12V6zM4 11h2v2H4v-2zm16 0H8v2h12v-2zM4 16h2v2H4v-2zm16 0H8v2h12v-2z\" fill=\"currentColor\"><\/path><\/svg><svg style=\"fill: #999;color:#999\" class=\"arrow-unsorted-368013\" xmlns=\"http:\/\/www.w3.org\/2000\/svg\" width=\"10px\" height=\"10px\" viewBox=\"0 0 24 24\" version=\"1.2\" baseProfile=\"tiny\"><path d=\"M18.2 9.3l-6.2-6.3-6.2 6.3c-.2.2-.3.4-.3.7s.1.5.3.7c.2.2.4.3.7.3h11c.3 0 .5-.1.7-.3.2-.2.3-.5.3-.7s-.1-.5-.3-.7zM5.8 14.7l6.2 6.3 6.2-6.3c.2-.2.3-.5.3-.7s-.1-.5-.3-.7c-.2-.2-.4-.3-.7-.3h-11c-.3 0-.5.1-.7.3-.2.2-.3.5-.3.7s.1.5.3.7z\"\/><\/svg><\/span><\/span><\/label><input type=\"checkbox\"  id=\"ez-toc-cssicon-toggle-item-69fc897cf371a\"  aria-label=\"Toggle\" \/><nav><ul class='ez-toc-list ez-toc-list-level-1 ' ><li class='ez-toc-page-1 ez-toc-heading-level-2'><a class=\"ez-toc-link ez-toc-heading-1\" href=\"https:\/\/roboticsbackend.com\/rclcpp-params-tutorial-get-set-ros2-params-with-cpp\/#Setup_code_and_declare_ROS2_params_with_rclcpp\" >Setup code and declare ROS2 params with rclcpp<\/a><ul class='ez-toc-list-level-3' ><li class='ez-toc-heading-level-3'><a class=\"ez-toc-link ez-toc-heading-2\" href=\"https:\/\/roboticsbackend.com\/rclcpp-params-tutorial-get-set-ros2-params-with-cpp\/#Declare_params_with_rclcpp\" >Declare params with rclcpp<\/a><\/li><li class='ez-toc-page-1 ez-toc-heading-level-3'><a class=\"ez-toc-link ez-toc-heading-3\" href=\"https:\/\/roboticsbackend.com\/rclcpp-params-tutorial-get-set-ros2-params-with-cpp\/#Run_your_node\" >Run your node<\/a><\/li><\/ul><\/li><li class='ez-toc-page-1 ez-toc-heading-level-2'><a class=\"ez-toc-link ez-toc-heading-4\" href=\"https:\/\/roboticsbackend.com\/rclcpp-params-tutorial-get-set-ros2-params-with-cpp\/#Get_params_with_rclcpp\" >Get params with rclcpp<\/a><ul class='ez-toc-list-level-3' ><li class='ez-toc-heading-level-3'><a class=\"ez-toc-link ez-toc-heading-5\" href=\"https:\/\/roboticsbackend.com\/rclcpp-params-tutorial-get-set-ros2-params-with-cpp\/#Get_params_one_by_one\" >Get params one by one<\/a><\/li><li class='ez-toc-page-1 ez-toc-heading-level-3'><a class=\"ez-toc-link ez-toc-heading-6\" href=\"https:\/\/roboticsbackend.com\/rclcpp-params-tutorial-get-set-ros2-params-with-cpp\/#Get_a_list_of_params\" >Get a list of params<\/a><\/li><li class='ez-toc-page-1 ez-toc-heading-level-3'><a class=\"ez-toc-link ez-toc-heading-7\" href=\"https:\/\/roboticsbackend.com\/rclcpp-params-tutorial-get-set-ros2-params-with-cpp\/#Set_default_values\" >Set default values<\/a><\/li><\/ul><\/li><li class='ez-toc-page-1 ez-toc-heading-level-2'><a class=\"ez-toc-link ez-toc-heading-8\" href=\"https:\/\/roboticsbackend.com\/rclcpp-params-tutorial-get-set-ros2-params-with-cpp\/#Set_params_with_rclcpp\" >Set params with rclcpp<\/a><\/li><li class='ez-toc-page-1 ez-toc-heading-level-2'><a class=\"ez-toc-link ez-toc-heading-9\" href=\"https:\/\/roboticsbackend.com\/rclcpp-params-tutorial-get-set-ros2-params-with-cpp\/#Allow_undeclared_parameters_with_rclcpp\" >Allow undeclared parameters with rclcpp<\/a><\/li><li class='ez-toc-page-1 ez-toc-heading-level-2'><a class=\"ez-toc-link ez-toc-heading-10\" href=\"https:\/\/roboticsbackend.com\/rclcpp-params-tutorial-get-set-ros2-params-with-cpp\/#rclcpp_parameter_callback\" >rclcpp parameter callback<\/a><\/li><li class='ez-toc-page-1 ez-toc-heading-level-2'><a class=\"ez-toc-link ez-toc-heading-11\" href=\"https:\/\/roboticsbackend.com\/rclcpp-params-tutorial-get-set-ros2-params-with-cpp\/#Going_further_with_ROS2_params\" >Going further with ROS2 params<\/a><\/li><\/ul><\/nav><\/div>\n<h2><span class=\"ez-toc-section\" id=\"Setup_code_and_declare_ROS2_params_with_rclcpp\"><\/span>Setup code and declare ROS2 params with rclcpp<span class=\"ez-toc-section-end\"><\/span><\/h2>\n<p>Before you use a ROS2 param in your Cpp code, you must declare it. If you don&#8217;t do that, you won&#8217;t be able to access it and you&#8217;ll get an error instead (rclcpp::exceptions::ParameterNotDeclaredException).<\/p>\n<h3><span class=\"ez-toc-section\" id=\"Declare_params_with_rclcpp\"><\/span>Declare params with rclcpp<span class=\"ez-toc-section-end\"><\/span><\/h3>\n<p>Let&#8217;s declare 3 parameters in the constructor of our <a href=\"https:\/\/roboticsbackend.com\/write-minimal-ros2-cpp-node\/\">ROS2 Cpp node<\/a>.<\/p>\n<pre class=\"EnlighterJSRAW\" data-enlighter-language=\"cpp\">#include \"rclcpp\/rclcpp.hpp\"\n\nclass TestParams : public rclcpp::Node\n{\npublic:\n    TestParams() : Node(\"test_params_rclcpp\") {\n        this-&gt;declare_parameter(\"my_str\", rclcpp::PARAMETER_STRING);\n        this-&gt;declare_parameter(\"my_int\", rclcpp::PARAMETER_INTEGER);\n        this-&gt;declare_parameter(\"my_double_array\", rclcpp::PARAMETER_DOUBLE_ARRAY);\n    }\n\nprivate:\n};\n\n\/\/ Code below is just to start the node\nint main(int argc, char **argv)\n{\n    rclcpp::init(argc, argv);\n    auto node = std::make_shared&lt;TestParams&gt;();\n    rclcpp::spin(node);\n    rclcpp::shutdown();\n    return 0;\n}<\/pre>\n<p>Make sure to provide the type for each parameter (or a default value, see more later). For the type, just start with &#8220;rclcpp::PARAMETER_&#8221; and you should see all available types using auto-completion.<\/p>\n<p>If, at some point, you need to undeclare a parameter, you can do so with <code class=\"EnlighterJSRAW\" data-enlighter-language=\"cpp\">undeclare_parameter(param_name)<\/code>, for example <code class=\"EnlighterJSRAW\" data-enlighter-language=\"cpp\">this-&gt;undeclare_parameter(\"my_str\");<\/code>.<\/p>\n<h3><span class=\"ez-toc-section\" id=\"Run_your_node\"><\/span>Run your node<span class=\"ez-toc-section-end\"><\/span><\/h3>\n<p>Here are the commands we&#8217;ll use to run the node:<\/p>\n<ul>\n<li>Without any parameter&#8217;s value set:<\/li>\n<\/ul>\n<pre class=\"EnlighterJSRAW\" data-enlighter-language=\"shell\" data-enlighter-linenumbers=\"false\">$ ros2 run ros2_tutorials test_params_rclcpp<\/pre>\n<ul>\n<li>With parameters which correctly match the ones we declared in the code:<\/li>\n<\/ul>\n<pre class=\"EnlighterJSRAW\" data-enlighter-language=\"shell\" data-enlighter-linenumbers=\"false\">$ ros2 run ros2_tutorials test_params_rclcpp --ros-args -p my_str:=\"Hello Cpp\" -p my_int:=12 -p my_double_array:=\"[3.3, 4.4, 5.5]\"<\/pre>\n<p>You can also use a <a href=\"https:\/\/roboticsbackend.com\/ros2-launch-file-example\/\">launch file<\/a> to start everything without manually typing the parameters in the terminal (improvement: <a href=\"https:\/\/roboticsbackend.com\/ros2-yaml-params\/\">use a YAML file to store your params<\/a>).<\/p>\n<pre class=\"EnlighterJSRAW\" data-enlighter-language=\"python\">from launch import LaunchDescription\nfrom launch_ros.actions import Node\n\ndef generate_launch_description():\n    return LaunchDescription([\n        Node(\n            package='ros2_tutorials',\n            executable='test_params_rclcpp',\n            parameters=[\n                {'my_str': 'Hello Cpp'},\n                {'my_int': 12},\n                {'my_double_array': [3.3, 4.4, 5.5]}\n            ],\n            output='screen',\n            emulate_tty=True\n        )\n    ])<\/pre>\n<p>You can experiment running your node with our without setting values for parameters. Also, try to see what happens when you set a value for a parameter which was not declared (hint: the parameter won&#8217;t appear when you do <code class=\"EnlighterJSRAW\" data-enlighter-language=\"shell\">ros2 param list<\/code>).<\/p>\n<p>For a more detail test, check out the <a href=\"https:\/\/roboticsbackend.com\/rclpy-params-tutorial-get-set-ros2-params-with-python\/#Run_your_node_with_params\">tests made in the Python version of this tutorial<\/a>.<\/p>\n<h2><span class=\"ez-toc-section\" id=\"Get_params_with_rclcpp\"><\/span>Get params with rclcpp<span class=\"ez-toc-section-end\"><\/span><\/h2>\n<p>Your parameters have been declared from within your node. Now you can get their value.<\/p>\n<h3><span class=\"ez-toc-section\" id=\"Get_params_one_by_one\"><\/span>Get params one by one<span class=\"ez-toc-section-end\"><\/span><\/h3>\n<pre class=\"EnlighterJSRAW\" data-enlighter-language=\"cpp\">TestParams() : Node(\"test_params_rclcpp\")\n{\n    this-&gt;declare_parameter(\"my_str\", rclcpp::PARAMETER_STRING);\n    this-&gt;declare_parameter(\"my_int\", rclcpp::PARAMETER_INTEGER);\n    this-&gt;declare_parameter(\"my_double_array\", rclcpp::PARAMETER_DOUBLE_ARRAY);\n\n    rclcpp::Parameter str_param = this-&gt;get_parameter(\"my_str\");\n    rclcpp::Parameter int_param = this-&gt;get_parameter(\"my_int\");\n    rclcpp::Parameter double_array_param = this-&gt;get_parameter(\"my_double_array\");\n\n    std::string my_str = str_param.as_string();\n    int my_int = int_param.as_int();\n    std::vector&lt;double&gt; my_double_array = double_array_param.as_double_array();\n\n    RCLCPP_INFO(this-&gt;get_logger(), \"str: %s, int: %s, double[]: %s\",\n                str_param.value_to_string().c_str(),\n                int_param.value_to_string().c_str(),\n                double_array_param.value_to_string().c_str());\n}<\/pre>\n<p>The <code class=\"EnlighterJSRAW\" data-enlighter-language=\"cpp\">get_parameter(param_name)<\/code> method will return the parameter as a rclcpp::Parameter object.<\/p>\n<p>Then, to get the parameter&#8217;s value in the correct type, you can use a helper method &#8211; there is one for each parameter type: <code class=\"EnlighterJSRAW\" data-enlighter-language=\"cpp\">as_string()<\/code>, <code class=\"EnlighterJSRAW\" data-enlighter-language=\"cpp\">as_int()<\/code>, <code class=\"EnlighterJSRAW\" data-enlighter-language=\"cpp\">as_double()<\/code>, <code class=\"EnlighterJSRAW\" data-enlighter-language=\"cpp\">as_bool()<\/code>, <code class=\"EnlighterJSRAW\" data-enlighter-language=\"cpp\">as_string_array()<\/code>, <code class=\"EnlighterJSRAW\" data-enlighter-language=\"cpp\">as_int_array()<\/code>, <code class=\"EnlighterJSRAW\" data-enlighter-language=\"cpp\">as_double_array()<\/code>, <code class=\"EnlighterJSRAW\" data-enlighter-language=\"cpp\">as_bool_array()<\/code>, <code class=\"EnlighterJSRAW\" data-enlighter-language=\"cpp\">as_byte_array()<\/code>.<\/p>\n<p>For example, for a string array: <code class=\"EnlighterJSRAW\" data-enlighter-language=\"cpp\">std::vector&lt;std::string&gt; param_value = param.as_string_array();<\/code>. Use the <code class=\"EnlighterJSRAW\" data-enlighter-language=\"cpp\">auto<\/code> keyword for more simplicity: <code class=\"EnlighterJSRAW\" data-enlighter-language=\"cpp\">auto param_value = param.as_string_array();<\/code>.<\/p>\n<p>You also get another helper method, useful for logging: <code class=\"EnlighterJSRAW\" data-enlighter-language=\"cpp\">value_to_string()<\/code>. This will convert the parameter &#8211; with any type &#8211; to a string representation.<\/p>\n<p>Another way to get params:<\/p>\n<pre class=\"EnlighterJSRAW\" data-enlighter-language=\"cpp\">...\nrclcpp::Parameter str_param;\nrclcpp::Parameter int_param;\nrclcpp::Parameter double_array_param;\n\nthis-&gt;get_parameter(\"my_str\", str_param);\nthis-&gt;get_parameter(\"my_int\", int_param);\nthis-&gt;get_parameter(\"my_double_array\", double_array_param);\n...<\/pre>\n<p>The main difference between the 2 methods is how you&#8217;ll handle errors when you try to get a parameter which was not declared.<\/p>\n<p>With the first one, you get a &#8220;rclcpp::exceptions::ParameterNotDeclaredException&#8221; exception. With the second one, the method returns a boolean telling you if the value could be retrieved (= declared + set).<\/p>\n<h3><span class=\"ez-toc-section\" id=\"Get_a_list_of_params\"><\/span>Get a list of params<span class=\"ez-toc-section-end\"><\/span><\/h3>\n<p>You can get multiple params at once with <code class=\"EnlighterJSRAW\" data-enlighter-language=\"cpp\">get_parameters(param_list)<\/code>.<\/p>\n<pre class=\"EnlighterJSRAW\" data-enlighter-language=\"cpp\">...\nstd::vector&lt;std::string&gt; param_names = {\"my_str\", \"my_int\", \"my_double_array\"};\n\nstd::vector&lt;rclcpp::Parameter&gt; params = this-&gt;get_parameters(param_names);\n\nfor (auto &amp;param : params)\n{\n    RCLCPP_INFO(this-&gt;get_logger(), \"param name: %s, value: %s\",\n                param.get_name().c_str(), param.value_to_string().c_str());\n}\n...<\/pre>\n<p>You can easily retrieve which param is which, using the <code class=\"EnlighterJSRAW\" data-enlighter-language=\"cpp\">get_name()<\/code> method.<\/p>\n<h3><span class=\"ez-toc-section\" id=\"Set_default_values\"><\/span>Set default values<span class=\"ez-toc-section-end\"><\/span><\/h3>\n<p>You can set default values for your parameters directly when you declare them.<\/p>\n<pre class=\"EnlighterJSRAW\" data-enlighter-language=\"cpp\">...\nthis-&gt;declare_parameter(\"my_str\", \"Default for string\");\nthis-&gt;declare_parameter(\"my_int\", 42);\nthis-&gt;declare_parameter(\"my_double_array\", std::vector&lt;double&gt;{7.7, 8.8});\n...<\/pre>\n<p>If you run your node with no parameter:<\/p>\n<pre class=\"EnlighterJSRAW\" data-enlighter-language=\"shell\" data-enlighter-linenumbers=\"false\">$ ros2 run ros2_tutorials test_params_rclcpp\n[INFO] [test_params_rclcpp]: str: Default for string, int: 42, double[]: [7.7, 8.8]<\/pre>\n<p>The default values for parameters were applied. This way you can ensure that a parameter is never &#8220;null&#8221;.<\/p>\n<h2><span class=\"ez-toc-section\" id=\"Set_params_with_rclcpp\"><\/span>Set params with rclcpp<span class=\"ez-toc-section-end\"><\/span><\/h2>\n<p>You can set (and impose) a value for a ROS2 parameter, directly from you node. Note that it&#8217;s different from setting a default value. A default value will only be used if no other value is passed to the node. Setting a parameter from your node means that it will override any value previously set, from inside or outside the node.<\/p>\n<p>Here&#8217;s how to set parameters one by one:<\/p>\n<pre class=\"EnlighterJSRAW\" data-enlighter-language=\"cpp\">TestParams() : Node(\"test_params_rclcpp\")\n{\n    this-&gt;declare_parameter(\"my_str\", rclcpp::PARAMETER_STRING); \n    this-&gt;declare_parameter(\"my_int\", rclcpp::PARAMETER_INTEGER); \n    this-&gt;declare_parameter(\"my_double_array\", rclcpp::PARAMETER_DOUBLE_ARRAY);\n\n    rclcpp::Parameter str_param(\"my_str\", \"Hola from code\");\n    this-&gt;set_parameter(str_param);\n\n    \/\/ you can also do:\n\n    this-&gt;set_parameter(rclcpp::Parameter(\"my_int\", 77));\n    this-&gt;set_parameter(rclcpp::Parameter(\"my_double_array\", std::vector&lt;double&gt;{8.8, 9.9}));\n}<\/pre>\n<p>Simply create a Parameter object, using 2 arguments: the parameter&#8217;s name and value.<\/p>\n<p>If you now start the node, you will see that the 3 parameters are set, and the default value for &#8220;my_str&#8221; parameter is not used.<\/p>\n<pre class=\"EnlighterJSRAW\" data-enlighter-language=\"shell\" data-enlighter-linenumbers=\"false\">$ ros2 run ros2_tutorials test_params_rclcpp\n\n# In another terminal:\n$ ros2 param get \/test_params_rclcpp my_str\nString value is: Hola from code<\/pre>\n<p>You can also set multiple parameters at once:<\/p>\n<pre class=\"EnlighterJSRAW\" data-enlighter-language=\"cpp\">...\nthis-&gt;set_parameters(std::vector&lt;rclcpp::Parameter&gt;{\n    rclcpp::Parameter(\"my_str\", \"Hola from code\"),\n    rclcpp::Parameter(\"my_int\", 77),\n    rclcpp::Parameter(\"my_double_array\", std::vector&lt;double&gt;{8.8, 9.9})\n});\n...<\/pre>\n<h2><span class=\"ez-toc-section\" id=\"Allow_undeclared_parameters_with_rclcpp\"><\/span>Allow undeclared parameters with rclcpp<span class=\"ez-toc-section-end\"><\/span><\/h2>\n<p>In ROS2 the way to work with params is to always declare them before you use them.<\/p>\n<p>In some specific situations you might want to allow undeclared parameters. For example if your node is not able to know every parameter&#8217;s name when it&#8217;s started. Maybe your application requires you to dynamically set new parameters (with new names) when you start, or to add parameters after launch time.<\/p>\n<p>Well, there is a solution for that. Note, however, that you should always use the ROS2 way of doing things &#8211; declaring every parameter. Allowing undeclared parameters should only be done when you don&#8217;t have any other choice.<\/p>\n<pre class=\"EnlighterJSRAW\" data-enlighter-language=\"cpp\">TestParams() : Node(\"test_params_rclcpp\",\n                    rclcpp::NodeOptions()\n                        .allow_undeclared_parameters(true)\n                        .automatically_declare_parameters_from_overrides(true))\n{\n    rclcpp::Parameter str_param;\n    rclcpp::Parameter int_param;\n    rclcpp::Parameter double_array_param;\n\n    this-&gt;get_parameter_or(\"my_str\", str_param, rclcpp::Parameter(\"my_str\", \"Hi\"));\n    this-&gt;get_parameter_or(\"my_int\", int_param, rclcpp::Parameter(\"my_int\", 48));\n    this-&gt;get_parameter_or(\"my_double_array\", double_array_param,\n                           rclcpp::Parameter(\"my_double_array\", std::vector&lt;double&gt;{12.12, 13.13}));\n\n    RCLCPP_INFO(this-&gt;get_logger(), \"str: %s, int: %s, double[]: %s\",\n                str_param.value_to_string().c_str(),\n                int_param.value_to_string().c_str(),\n                double_array_param.value_to_string().c_str());\n}<\/pre>\n<p>In the node&#8217;s constructor you have to pass some additional node options, through the NodeOptions object with 2 flags set as true:<\/p>\n<ul>\n<li>allow_undeclared_parameters.<\/li>\n<li>automatically_declare_parameters_from_overrides.<\/li>\n<\/ul>\n<p>Here in this example I&#8217;ve directly created the NodeOptions object in the constructor, but you can also instantiate it in your main and pass it as a reference.<\/p>\n<p>So, when running this node, any parameter that you set from outside the node will be declared and set, even if you don&#8217;t declare it from within the node. Also you won&#8217;t get any error if you try to access a parameter which was not declared before. If the parameter doesn&#8217;t exist, you&#8217;ll just get a null value. That&#8217;s why, when doing this, it&#8217;s better to always set a default value for each parameter.<\/p>\n<p>To get a parameter with those settings, use the <code class=\"EnlighterJSRAW\" data-enlighter-language=\"cpp\">get_parameter_or(param_name, param_object, default_param)<\/code> method. It will fill the param_object with either the retrieved parameter (if it exists), or the default value.<\/p>\n<p>If we start this node with those 2 parameters:<\/p>\n<pre class=\"EnlighterJSRAW\" data-enlighter-language=\"shell\" data-enlighter-linenumbers=\"false\">$ ros2 run ros2_tutorials test_params_rclcpp --ros-args -p my_int:=55 -p intruder:=\"You'll see me in the list\"\n[INFO] [test_params_rclcpp]: str: Hi, int: 55, double[]: [12.12, 13.13]\n\n# In another terminal:\n$ ros2 param list\n\/test_params_rclcpp:\n  intruder\n  my_int\n  use_sim_time\n$ ros2 param get \/test_params_rclcpp intruder \nString value is: You'll see me in the list<\/pre>\n<p>The &#8220;my_int&#8221; parameter is declared because we set it from command line. The node will retrieve the correct value. The 2 other parameters are not declared, default values will be used.<\/p>\n<p>Note that the additional undeclared parameter appears on the list and you can get its value.<\/p>\n<p>A final note on this: by default, do what ROS2 suggests that you do. Declare all parameters you&#8217;ll need before you use them. Only allow undeclared parameters if you don&#8217;t have the choice.<\/p>\n<h2><span class=\"ez-toc-section\" id=\"rclcpp_parameter_callback\"><\/span>rclcpp parameter callback<span class=\"ez-toc-section-end\"><\/span><\/h2>\n<p>Even after you&#8217;ve declared and set your parameters, you can modify them from outside your node. And, if you wish to, you can get notified from within your node, so you can do something whenever a parameter has been changed.<\/p>\n<p>(for ROS1 users, this is very similar to dynamic_reconfigure, but here it&#8217;s directly integrated in the node&#8217;s API, you don&#8217;t have to setup anything else.)<\/p>\n<pre class=\"EnlighterJSRAW\" data-enlighter-language=\"cpp\">#include \"rclcpp\/rclcpp.hpp\"\n#include \"rcl_interfaces\/msg\/set_parameters_result.hpp\"\n\nclass TestParams : public rclcpp::Node\n{\npublic:\n    rcl_interfaces::msg::SetParametersResult parametersCallback(\n        const std::vector&lt;rclcpp::Parameter&gt; &amp;parameters)\n    {\n        rcl_interfaces::msg::SetParametersResult result;\n        result.successful = true;\n        result.reason = \"success\";\n        for (const auto &amp;parameter : parameters)\n        {\n            if (parameter.get_name() == \"my_str\" &amp;&amp;\n                parameter.get_type() == rclcpp::ParameterType::PARAMETER_STRING)\n            {\n                my_str_ = parameter.as_string();\n                RCLCPP_INFO(this-&gt;get_logger(), \"Parameter 'my_str' changed: %s\", my_str_.c_str());\n            }\n        }\n        return result;\n    }\n\n    TestParams() : Node(\"test_params_rclcpp\")\n    {\n        this-&gt;declare_parameter(\"my_str\", \"default value\");\n        my_str_ = this-&gt;get_parameter(\"my_str\").as_string();\n\n        this-&gt;set_on_parameters_set_callback(\n            std::bind(&amp;TestParams::parametersCallback, this, std::placeholders::_1));\n    }\n\nprivate:\n    std::string my_str_;\n};<\/pre>\n<p>Use this template to handle any change made to any parameters you&#8217;ve declared. Check for the name and the type to be sure the value is correct.<\/p>\n<p>Now what you do with this callback is up to you and depends on your application (to go further on this, check out this more complete <a href=\"https:\/\/roboticsbackend.com\/ros2-rclcpp-parameter-callback\/\">rclcpp parameter callback tutorial<\/a>).<\/p>\n<h2><span class=\"ez-toc-section\" id=\"Going_further_with_ROS2_params\"><\/span>Going further with ROS2 params<span class=\"ez-toc-section-end\"><\/span><\/h2>\n<p>In this tutorial you&#8217;ve learned how to get and set ROS2 parameters with rclcpp, from your Cpp node. One thing worth repeating: don&#8217;t forget to declare your parameters before you use them.<\/p>\n<p>To go further from this point:<\/p>\n<ul>\n<li><a href=\"https:\/\/roboticsbackend.com\/rclpy-params-tutorial-get-set-ros2-params-with-python\/\">Learn how to do the same in Python with rclpy<\/a>.<\/li>\n<li><a href=\"https:\/\/roboticsbackend.com\/ros2-yaml-params\/\">Load your parameters from a YAML config file instead of one by one<\/a> (best practice for scaling).<\/li>\n<\/ul>\n<p>Also, as ROS2 parameters are specific to a node, you can only be sure your parameters exist as long as your node is alive. What if you want some parameters to be in the global scope, available for all nodes? Well, if you ever need to have some global settings, one way to solve that issue is to create a <a href=\"https:\/\/roboticsbackend.com\/ros2-global-parameters\/\">node holding global parameters<\/a>. Launch this node first and keep it alive as long as your application is alive. Then, other nodes from your application will be able to use ROS2 communication features to get params from this &#8220;global param node&#8221;.<\/p>\n","protected":false},"excerpt":{"rendered":"<p>In this rclcpp params tutorial you&#8217;ll see how to get and set ROS2 params with rclcpp, in a Cpp node. If you want to do the same with Python, check out the rclpy tutorial. Setup code and declare ROS2 params with rclcpp Before you use a ROS2 param in your Cpp code, you must declare &#8230; <a title=\"rclcpp Params Tutorial &#8211; Get and Set ROS2 Params with Cpp\" class=\"read-more\" href=\"https:\/\/roboticsbackend.com\/rclcpp-params-tutorial-get-set-ros2-params-with-cpp\/\" aria-label=\"Read more about rclcpp Params Tutorial &#8211; Get and Set ROS2 Params with Cpp\">Read more<\/a><\/p>\n","protected":false},"author":1,"featured_media":0,"comment_status":"closed","ping_status":"open","sticky":false,"template":"","format":"standard","meta":{"footnotes":""},"categories":[6],"tags":[],"class_list":["post-1987","post","type-post","status-publish","format-standard","hentry","category-ros2"],"yoast_head":"<!-- This site is optimized with the Yoast SEO plugin v27.1.1 - https:\/\/yoast.com\/product\/yoast-seo-wordpress\/ -->\n<title>rclcpp Params Tutorial - Get and Set ROS2 Params with Cpp - The Robotics Back-End<\/title>\n<meta name=\"description\" content=\"Learn how to set and get rclcpp params from within your ROS2 Cpp node. Complete example showing you how to declare params, set a callback, etc.\" \/>\n<meta name=\"robots\" content=\"index, follow, max-snippet:-1, max-image-preview:large, max-video-preview:-1\" \/>\n<link rel=\"canonical\" href=\"https:\/\/roboticsbackend.com\/rclcpp-params-tutorial-get-set-ros2-params-with-cpp\/\" \/>\n<meta property=\"og:locale\" content=\"en_US\" \/>\n<meta property=\"og:type\" content=\"article\" \/>\n<meta property=\"og:title\" content=\"rclcpp Params Tutorial - Get and Set ROS2 Params with Cpp - The Robotics Back-End\" \/>\n<meta property=\"og:description\" content=\"Learn how to set and get rclcpp params from within your ROS2 Cpp node. Complete example showing you how to declare params, set a callback, etc.\" \/>\n<meta property=\"og:url\" content=\"https:\/\/roboticsbackend.com\/rclcpp-params-tutorial-get-set-ros2-params-with-cpp\/\" \/>\n<meta property=\"og:site_name\" content=\"The Robotics Back-End\" \/>\n<meta property=\"article:published_time\" content=\"2020-06-22T09:13:17+00:00\" \/>\n<meta property=\"article:modified_time\" content=\"2023-04-27T12:30:53+00:00\" \/>\n<meta name=\"author\" content=\"ed\" \/>\n<meta name=\"twitter:card\" content=\"summary_large_image\" \/>\n<meta name=\"twitter:creator\" content=\"@RoboticsBackend\" \/>\n<meta name=\"twitter:site\" content=\"@RoboticsBackend\" \/>\n<meta name=\"twitter:label1\" content=\"Written by\" \/>\n\t<meta name=\"twitter:data1\" content=\"ed\" \/>\n\t<meta name=\"twitter:label2\" content=\"Est. reading time\" \/>\n\t<meta name=\"twitter:data2\" content=\"8 minutes\" \/>\n<script type=\"application\/ld+json\" class=\"yoast-schema-graph\">{\"@context\":\"https:\/\/schema.org\",\"@graph\":[{\"@type\":\"Article\",\"@id\":\"https:\/\/roboticsbackend.com\/rclcpp-params-tutorial-get-set-ros2-params-with-cpp\/#article\",\"isPartOf\":{\"@id\":\"https:\/\/roboticsbackend.com\/rclcpp-params-tutorial-get-set-ros2-params-with-cpp\/\"},\"author\":{\"name\":\"ed\",\"@id\":\"https:\/\/roboticsbackend.com\/#\/schema\/person\/a20832f15e39847d8eea5be981767353\"},\"headline\":\"rclcpp Params Tutorial &#8211; Get and Set ROS2 Params with Cpp\",\"datePublished\":\"2020-06-22T09:13:17+00:00\",\"dateModified\":\"2023-04-27T12:30:53+00:00\",\"mainEntityOfPage\":{\"@id\":\"https:\/\/roboticsbackend.com\/rclcpp-params-tutorial-get-set-ros2-params-with-cpp\/\"},\"wordCount\":1288,\"publisher\":{\"@id\":\"https:\/\/roboticsbackend.com\/#organization\"},\"articleSection\":[\"ROS2 Tutorials\"],\"inLanguage\":\"en-US\"},{\"@type\":\"WebPage\",\"@id\":\"https:\/\/roboticsbackend.com\/rclcpp-params-tutorial-get-set-ros2-params-with-cpp\/\",\"url\":\"https:\/\/roboticsbackend.com\/rclcpp-params-tutorial-get-set-ros2-params-with-cpp\/\",\"name\":\"rclcpp Params Tutorial - Get and Set ROS2 Params with Cpp - The Robotics Back-End\",\"isPartOf\":{\"@id\":\"https:\/\/roboticsbackend.com\/#website\"},\"datePublished\":\"2020-06-22T09:13:17+00:00\",\"dateModified\":\"2023-04-27T12:30:53+00:00\",\"description\":\"Learn how to set and get rclcpp params from within your ROS2 Cpp node. Complete example showing you how to declare params, set a callback, etc.\",\"breadcrumb\":{\"@id\":\"https:\/\/roboticsbackend.com\/rclcpp-params-tutorial-get-set-ros2-params-with-cpp\/#breadcrumb\"},\"inLanguage\":\"en-US\",\"potentialAction\":[{\"@type\":\"ReadAction\",\"target\":[\"https:\/\/roboticsbackend.com\/rclcpp-params-tutorial-get-set-ros2-params-with-cpp\/\"]}]},{\"@type\":\"BreadcrumbList\",\"@id\":\"https:\/\/roboticsbackend.com\/rclcpp-params-tutorial-get-set-ros2-params-with-cpp\/#breadcrumb\",\"itemListElement\":[{\"@type\":\"ListItem\",\"position\":1,\"name\":\"Home\",\"item\":\"https:\/\/roboticsbackend.com\/\"},{\"@type\":\"ListItem\",\"position\":2,\"name\":\"rclcpp Params Tutorial &#8211; Get and Set ROS2 Params with Cpp\"}]},{\"@type\":\"WebSite\",\"@id\":\"https:\/\/roboticsbackend.com\/#website\",\"url\":\"https:\/\/roboticsbackend.com\/\",\"name\":\"The Robotics Back-End\",\"description\":\"Program Robots, Step by Step\",\"publisher\":{\"@id\":\"https:\/\/roboticsbackend.com\/#organization\"},\"potentialAction\":[{\"@type\":\"SearchAction\",\"target\":{\"@type\":\"EntryPoint\",\"urlTemplate\":\"https:\/\/roboticsbackend.com\/?s={search_term_string}\"},\"query-input\":{\"@type\":\"PropertyValueSpecification\",\"valueRequired\":true,\"valueName\":\"search_term_string\"}}],\"inLanguage\":\"en-US\"},{\"@type\":\"Organization\",\"@id\":\"https:\/\/roboticsbackend.com\/#organization\",\"name\":\"Robotics Back-End\",\"url\":\"https:\/\/roboticsbackend.com\/\",\"logo\":{\"@type\":\"ImageObject\",\"inLanguage\":\"en-US\",\"@id\":\"https:\/\/roboticsbackend.com\/#\/schema\/logo\/image\/\",\"url\":\"https:\/\/roboticsbackend.com\/wp-content\/uploads\/2020\/02\/logo_hd.png\",\"contentUrl\":\"https:\/\/roboticsbackend.com\/wp-content\/uploads\/2020\/02\/logo_hd.png\",\"width\":2500,\"height\":1875,\"caption\":\"Robotics Back-End\"},\"image\":{\"@id\":\"https:\/\/roboticsbackend.com\/#\/schema\/logo\/image\/\"},\"sameAs\":[\"https:\/\/x.com\/RoboticsBackend\"]},{\"@type\":\"Person\",\"@id\":\"https:\/\/roboticsbackend.com\/#\/schema\/person\/a20832f15e39847d8eea5be981767353\",\"name\":\"ed\",\"image\":{\"@type\":\"ImageObject\",\"inLanguage\":\"en-US\",\"@id\":\"https:\/\/roboticsbackend.com\/#\/schema\/person\/image\/\",\"url\":\"https:\/\/secure.gravatar.com\/avatar\/7b666620f11fb12df5674e1e1ee525afe3d4ceecdaa57f8c60f6a937a33e3427?s=96&d=identicon&r=g\",\"contentUrl\":\"https:\/\/secure.gravatar.com\/avatar\/7b666620f11fb12df5674e1e1ee525afe3d4ceecdaa57f8c60f6a937a33e3427?s=96&d=identicon&r=g\",\"caption\":\"ed\"}}]}<\/script>\n<!-- \/ Yoast SEO plugin. -->","yoast_head_json":{"title":"rclcpp Params Tutorial - Get and Set ROS2 Params with Cpp - The Robotics Back-End","description":"Learn how to set and get rclcpp params from within your ROS2 Cpp node. Complete example showing you how to declare params, set a callback, etc.","robots":{"index":"index","follow":"follow","max-snippet":"max-snippet:-1","max-image-preview":"max-image-preview:large","max-video-preview":"max-video-preview:-1"},"canonical":"https:\/\/roboticsbackend.com\/rclcpp-params-tutorial-get-set-ros2-params-with-cpp\/","og_locale":"en_US","og_type":"article","og_title":"rclcpp Params Tutorial - Get and Set ROS2 Params with Cpp - The Robotics Back-End","og_description":"Learn how to set and get rclcpp params from within your ROS2 Cpp node. Complete example showing you how to declare params, set a callback, etc.","og_url":"https:\/\/roboticsbackend.com\/rclcpp-params-tutorial-get-set-ros2-params-with-cpp\/","og_site_name":"The Robotics Back-End","article_published_time":"2020-06-22T09:13:17+00:00","article_modified_time":"2023-04-27T12:30:53+00:00","author":"ed","twitter_card":"summary_large_image","twitter_creator":"@RoboticsBackend","twitter_site":"@RoboticsBackend","twitter_misc":{"Written by":"ed","Est. reading time":"8 minutes"},"schema":{"@context":"https:\/\/schema.org","@graph":[{"@type":"Article","@id":"https:\/\/roboticsbackend.com\/rclcpp-params-tutorial-get-set-ros2-params-with-cpp\/#article","isPartOf":{"@id":"https:\/\/roboticsbackend.com\/rclcpp-params-tutorial-get-set-ros2-params-with-cpp\/"},"author":{"name":"ed","@id":"https:\/\/roboticsbackend.com\/#\/schema\/person\/a20832f15e39847d8eea5be981767353"},"headline":"rclcpp Params Tutorial &#8211; Get and Set ROS2 Params with Cpp","datePublished":"2020-06-22T09:13:17+00:00","dateModified":"2023-04-27T12:30:53+00:00","mainEntityOfPage":{"@id":"https:\/\/roboticsbackend.com\/rclcpp-params-tutorial-get-set-ros2-params-with-cpp\/"},"wordCount":1288,"publisher":{"@id":"https:\/\/roboticsbackend.com\/#organization"},"articleSection":["ROS2 Tutorials"],"inLanguage":"en-US"},{"@type":"WebPage","@id":"https:\/\/roboticsbackend.com\/rclcpp-params-tutorial-get-set-ros2-params-with-cpp\/","url":"https:\/\/roboticsbackend.com\/rclcpp-params-tutorial-get-set-ros2-params-with-cpp\/","name":"rclcpp Params Tutorial - Get and Set ROS2 Params with Cpp - The Robotics Back-End","isPartOf":{"@id":"https:\/\/roboticsbackend.com\/#website"},"datePublished":"2020-06-22T09:13:17+00:00","dateModified":"2023-04-27T12:30:53+00:00","description":"Learn how to set and get rclcpp params from within your ROS2 Cpp node. Complete example showing you how to declare params, set a callback, etc.","breadcrumb":{"@id":"https:\/\/roboticsbackend.com\/rclcpp-params-tutorial-get-set-ros2-params-with-cpp\/#breadcrumb"},"inLanguage":"en-US","potentialAction":[{"@type":"ReadAction","target":["https:\/\/roboticsbackend.com\/rclcpp-params-tutorial-get-set-ros2-params-with-cpp\/"]}]},{"@type":"BreadcrumbList","@id":"https:\/\/roboticsbackend.com\/rclcpp-params-tutorial-get-set-ros2-params-with-cpp\/#breadcrumb","itemListElement":[{"@type":"ListItem","position":1,"name":"Home","item":"https:\/\/roboticsbackend.com\/"},{"@type":"ListItem","position":2,"name":"rclcpp Params Tutorial &#8211; Get and Set ROS2 Params with Cpp"}]},{"@type":"WebSite","@id":"https:\/\/roboticsbackend.com\/#website","url":"https:\/\/roboticsbackend.com\/","name":"The Robotics Back-End","description":"Program Robots, Step by Step","publisher":{"@id":"https:\/\/roboticsbackend.com\/#organization"},"potentialAction":[{"@type":"SearchAction","target":{"@type":"EntryPoint","urlTemplate":"https:\/\/roboticsbackend.com\/?s={search_term_string}"},"query-input":{"@type":"PropertyValueSpecification","valueRequired":true,"valueName":"search_term_string"}}],"inLanguage":"en-US"},{"@type":"Organization","@id":"https:\/\/roboticsbackend.com\/#organization","name":"Robotics Back-End","url":"https:\/\/roboticsbackend.com\/","logo":{"@type":"ImageObject","inLanguage":"en-US","@id":"https:\/\/roboticsbackend.com\/#\/schema\/logo\/image\/","url":"https:\/\/roboticsbackend.com\/wp-content\/uploads\/2020\/02\/logo_hd.png","contentUrl":"https:\/\/roboticsbackend.com\/wp-content\/uploads\/2020\/02\/logo_hd.png","width":2500,"height":1875,"caption":"Robotics Back-End"},"image":{"@id":"https:\/\/roboticsbackend.com\/#\/schema\/logo\/image\/"},"sameAs":["https:\/\/x.com\/RoboticsBackend"]},{"@type":"Person","@id":"https:\/\/roboticsbackend.com\/#\/schema\/person\/a20832f15e39847d8eea5be981767353","name":"ed","image":{"@type":"ImageObject","inLanguage":"en-US","@id":"https:\/\/roboticsbackend.com\/#\/schema\/person\/image\/","url":"https:\/\/secure.gravatar.com\/avatar\/7b666620f11fb12df5674e1e1ee525afe3d4ceecdaa57f8c60f6a937a33e3427?s=96&d=identicon&r=g","contentUrl":"https:\/\/secure.gravatar.com\/avatar\/7b666620f11fb12df5674e1e1ee525afe3d4ceecdaa57f8c60f6a937a33e3427?s=96&d=identicon&r=g","caption":"ed"}}]}},"_links":{"self":[{"href":"https:\/\/roboticsbackend.com\/wp-json\/wp\/v2\/posts\/1987","targetHints":{"allow":["GET"]}}],"collection":[{"href":"https:\/\/roboticsbackend.com\/wp-json\/wp\/v2\/posts"}],"about":[{"href":"https:\/\/roboticsbackend.com\/wp-json\/wp\/v2\/types\/post"}],"author":[{"embeddable":true,"href":"https:\/\/roboticsbackend.com\/wp-json\/wp\/v2\/users\/1"}],"replies":[{"embeddable":true,"href":"https:\/\/roboticsbackend.com\/wp-json\/wp\/v2\/comments?post=1987"}],"version-history":[{"count":0,"href":"https:\/\/roboticsbackend.com\/wp-json\/wp\/v2\/posts\/1987\/revisions"}],"wp:attachment":[{"href":"https:\/\/roboticsbackend.com\/wp-json\/wp\/v2\/media?parent=1987"}],"wp:term":[{"taxonomy":"category","embeddable":true,"href":"https:\/\/roboticsbackend.com\/wp-json\/wp\/v2\/categories?post=1987"},{"taxonomy":"post_tag","embeddable":true,"href":"https:\/\/roboticsbackend.com\/wp-json\/wp\/v2\/tags?post=1987"}],"curies":[{"name":"wp","href":"https:\/\/api.w.org\/{rel}","templated":true}]}}