diff --git a/sros2/sros2/policy/schemas/policy.xsd b/sros2/sros2/policy/schemas/policy.xsd
index c1724221..da0e7c8f 100644
--- a/sros2/sros2/policy/schemas/policy.xsd
+++ b/sros2/sros2/policy/schemas/policy.xsd
@@ -10,18 +10,18 @@
-
+
-
+
-
+
-
+
diff --git a/sros2/test/sros2/commands/security/verbs/test_generate_policy.py b/sros2/test/sros2/commands/security/verbs/test_generate_policy.py
index 785f7463..118967ab 100644
--- a/sros2/test/sros2/commands/security/verbs/test_generate_policy.py
+++ b/sros2/test/sros2/commands/security/verbs/test_generate_policy.py
@@ -29,7 +29,7 @@
def test_generate_policy_topics():
with tempfile.TemporaryDirectory() as tmpdir:
# Create a test-specific enclave so that generate_policy can still init
- enclave = rclpy.Context()
+ context = rclpy.Context()
rclpy.init(enclave=enclave)
node = rclpy.create_node('test_generate_policy_topics_node', enclave=enclave)
@@ -72,7 +72,7 @@ def test_generate_policy_topics():
def test_generate_policy_services():
with tempfile.TemporaryDirectory() as tmpdir:
# Create a test-specific enclave so that generate_policy can still init
- enclave = rclpy.Context()
+ context = rclpy.Context()
rclpy.init(enclave=enclave)
node = rclpy.create_node('test_generate_policy_services_node', enclave=enclave)