From 9290736c5e96bc6d8fe03a52c7c4e33e7acb0d5e Mon Sep 17 00:00:00 2001
From: Tomoya Fujita <Tomoya.Fujita@sony.com>
Date: Wed, 27 Oct 2021 15:16:20 -0700
Subject: [PATCH] add reproducible test for loading parameter file.

Signed-off-by: Tomoya Fujita <Tomoya.Fujita@sony.com>
---
 prover_rclcpp/CMakeLists.txt                  |   1 +
 prover_rclcpp/src/ros2_1173.cpp               |  13 ++++++
 prover_rclpy/setup.py                         |   1 +
 .../src/__pycache__/__init__.cpython-38.pyc   | Bin 149 -> 149 bytes
 prover_rclpy/src/ros2_1173.py                 |  38 ++++++++++++++++++
 5 files changed, 53 insertions(+)
 create mode 100644 prover_rclcpp/src/ros2_1173.cpp
 create mode 100644 prover_rclpy/src/ros2_1173.py

diff --git a/prover_rclcpp/CMakeLists.txt b/prover_rclcpp/CMakeLists.txt
index 71835ab..eaba976 100644
--- a/prover_rclcpp/CMakeLists.txt
+++ b/prover_rclcpp/CMakeLists.txt
@@ -90,6 +90,7 @@ custom_executable(rmw_fastrtps_555)
 #custom_executable(ros2_946_pub)
 #custom_executable(ros2_946_sub)
 #custom_executable(ros2_1026)
+custom_executable(ros2_1173)
 
 #custom_executable(ros2cli_601)
 
diff --git a/prover_rclcpp/src/ros2_1173.cpp b/prover_rclcpp/src/ros2_1173.cpp
new file mode 100644
index 0000000..a46ea54
--- /dev/null
+++ b/prover_rclcpp/src/ros2_1173.cpp
@@ -0,0 +1,13 @@
+#include "rclcpp/rclcpp.hpp"
+
+int main(int argc, char ** argv)
+{
+  rclcpp::init(argc, argv);
+  rclcpp::NodeOptions options;
+  options.automatically_declare_parameters_from_overrides(true);
+
+  std::shared_ptr<rclcpp::Node> node = rclcpp::Node::make_shared("ParametersNode", options);
+
+  rclcpp::spin(node);
+  rclcpp::shutdown();
+}
\ No newline at end of file
diff --git a/prover_rclpy/setup.py b/prover_rclpy/setup.py
index c620020..532043a 100644
--- a/prover_rclpy/setup.py
+++ b/prover_rclpy/setup.py
@@ -40,6 +40,7 @@
             'rclpy_client_822 = src.rclpy_client_822:main',
             'rclpy_server_822 = src.rclpy_server_822:main',
             'rclpy_827 = src.rclpy_827:main',
+            'ros2_1173 = src.ros2_1173:main',
         ],
     },
 )
diff --git a/prover_rclpy/src/__pycache__/__init__.cpython-38.pyc b/prover_rclpy/src/__pycache__/__init__.cpython-38.pyc
index d4c4783624bf3ba2ed96316569b5ef3679f0d02b..034dd25c969b1ca48afcaf763ff7239647217e0f 100644
GIT binary patch
delta 19
ZcmbQrIF*q*l$V!_0SGpDmQUpF0stlB1V;b>

delta 19
ZcmbQrIF*q*l$V!_0SHv%d?#{u0RSRm1E&B0

diff --git a/prover_rclpy/src/ros2_1173.py b/prover_rclpy/src/ros2_1173.py
new file mode 100644
index 0000000..d77a16e
--- /dev/null
+++ b/prover_rclpy/src/ros2_1173.py
@@ -0,0 +1,38 @@
+# Refer to the following API:
+import rclpy
+from rclpy.node import Node
+from rcl_interfaces.msg import SetParametersResult
+
+class ParametersNode(Node):
+    def __init__(self):
+        super().__init__('ParametersNode', automatically_declare_parameters_from_overrides=True)
+        self.get_logger().info("Initialized Parameters Node.")
+        #self._timer = self.create_timer(1, self.printParam)
+        self.declare_parameter("self_declared_param", 45)
+        # self.set_parameters_callback(self.onParameterChange)
+        # self.add_on_set_parameters_callback(self.onParameterChange)
+
+    def printParam(self):
+        params = ["test", "group.list_param", "group.string_param", "group2.complex_param",
+                  "group.group2.float_param", "group.group2.bool_param"]
+        for p in params:
+            try:
+                obj = self.get_parameter(p)
+                value = obj._value
+                self.get_logger().info(f"Parameter {p}: {value} ({type(value)}), ({obj.type_})")
+            except rclpy.exceptions.ParameterNotDeclaredException:
+                self.get_logger().info(f"Parameter {p} not defined!")
+
+    def onParameterChange(self, params):
+        txt = "\n".join(f"   {p.name}={p.value}" for p in params)
+        self.get_logger().info("Parameter changed callback called! Changed parameters:\n" + txt)
+        return SetParametersResult(successful=True)
+
+def main(args=None):
+    rclpy.init(args=args)
+
+    node = ParametersNode()
+    rclpy.spin(node)
+
+    node.destroy_node()
+    rclpy.shutdown()