|
| 1 | +#!/usr/bin/env python3 |
| 2 | + |
| 3 | +# Copyright 2024 TIER IV, Inc. |
| 4 | +# |
| 5 | +# Licensed under the Apache License, Version 2.0 (the "License"); |
| 6 | +# you may not use this file except in compliance with the License. |
| 7 | +# You may obtain a copy of the License at |
| 8 | +# |
| 9 | +# http://www.apache.org/licenses/LICENSE-2.0 |
| 10 | +# |
| 11 | +# Unless required by applicable law or agreed to in writing, software |
| 12 | +# distributed under the License is distributed on an "AS IS" BASIS, |
| 13 | +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 14 | +# See the License for the specific language governing permissions and |
| 15 | +# limitations under the License. |
| 16 | + |
| 17 | +import os |
| 18 | +import unittest |
| 19 | + |
| 20 | +from ament_index_python import get_package_share_directory |
| 21 | +import launch |
| 22 | +from launch.actions import IncludeLaunchDescription |
| 23 | +from launch.launch_description_sources import AnyLaunchDescriptionSource |
| 24 | +from launch.logging import get_logger |
| 25 | +import launch_testing |
| 26 | +import pytest |
| 27 | +from rcl_interfaces.msg import Parameter |
| 28 | +from rcl_interfaces.msg import ParameterType |
| 29 | +from rcl_interfaces.msg import ParameterValue |
| 30 | +from rcl_interfaces.srv import SetParameters |
| 31 | +import rclpy |
| 32 | +import rclpy.qos |
| 33 | +from tier4_planning_msgs.msg import VelocityLimit |
| 34 | +from tier4_planning_msgs.msg import VelocityLimitClearCommand |
| 35 | + |
| 36 | +logger = get_logger(__name__) |
| 37 | + |
| 38 | + |
| 39 | +@pytest.mark.launch_test |
| 40 | +def generate_test_description(): |
| 41 | + test_external_velocity_limit_selector_launch_file = os.path.join( |
| 42 | + get_package_share_directory("autoware_external_velocity_limit_selector"), |
| 43 | + "launch", |
| 44 | + "external_velocity_limit_selector.launch.xml", |
| 45 | + ) |
| 46 | + external_velocity_limit_selector = IncludeLaunchDescription( |
| 47 | + AnyLaunchDescriptionSource(test_external_velocity_limit_selector_launch_file), |
| 48 | + ) |
| 49 | + |
| 50 | + return launch.LaunchDescription( |
| 51 | + [ |
| 52 | + external_velocity_limit_selector, |
| 53 | + # Start tests right away - no need to wait for anything |
| 54 | + launch_testing.actions.ReadyToTest(), |
| 55 | + ] |
| 56 | + ) |
| 57 | + |
| 58 | + |
| 59 | +class TestExternalVelocityLimitSelector(unittest.TestCase): |
| 60 | + @classmethod |
| 61 | + def setUpClass(cls): |
| 62 | + # Initialize the ROS context for the test node |
| 63 | + rclpy.init() |
| 64 | + |
| 65 | + @classmethod |
| 66 | + def tearDownClass(cls): |
| 67 | + # Shutdown the ROS context |
| 68 | + rclpy.shutdown() |
| 69 | + |
| 70 | + def velocity_limit_callback(self, msg): |
| 71 | + self.msg_buffer_ = msg |
| 72 | + |
| 73 | + def setUp(self): |
| 74 | + # Create a ROS node for tests |
| 75 | + self.test_node = rclpy.create_node("test_node") |
| 76 | + qos = rclpy.qos.QoSProfile(depth=1, durability=rclpy.qos.DurabilityPolicy.TRANSIENT_LOCAL) |
| 77 | + self.pub_api_limit_ = self.test_node.create_publisher( |
| 78 | + VelocityLimit, "/planning/scenario_planning/max_velocity_default", qos |
| 79 | + ) |
| 80 | + self.pub_internal_limit_ = self.test_node.create_publisher( |
| 81 | + VelocityLimit, "/planning/scenario_planning/max_velocity_candidates", qos |
| 82 | + ) |
| 83 | + self.pub_clear_limit_ = self.test_node.create_publisher( |
| 84 | + VelocityLimitClearCommand, "/planning/scenario_planning/clear_velocity_limit", qos |
| 85 | + ) |
| 86 | + self.msg_buffer_ = None |
| 87 | + self.velocity_limit_output_ = None |
| 88 | + self.test_node.create_subscription( |
| 89 | + VelocityLimit, |
| 90 | + "/planning/scenario_planning/max_velocity", |
| 91 | + self.velocity_limit_callback, |
| 92 | + 1, |
| 93 | + ) |
| 94 | + |
| 95 | + def wait_for_output(self): |
| 96 | + while not self.msg_buffer_: |
| 97 | + rclpy.spin_once(self.test_node, timeout_sec=0.1) |
| 98 | + self.velocity_limit_output_ = self.msg_buffer_ |
| 99 | + self.msg_buffer_ = None |
| 100 | + |
| 101 | + def tearDown(self): |
| 102 | + self.test_node.destroy_node() |
| 103 | + |
| 104 | + def update_max_vel_param(self, max_vel): |
| 105 | + set_params_client = self.test_node.create_client( |
| 106 | + SetParameters, "/external_velocity_limit_selector/set_parameters" |
| 107 | + ) |
| 108 | + while not set_params_client.wait_for_service(timeout_sec=1.0): |
| 109 | + continue |
| 110 | + set_params_request = SetParameters.Request() |
| 111 | + set_params_request.parameters = [ |
| 112 | + Parameter( |
| 113 | + name="max_vel", |
| 114 | + value=ParameterValue(type=ParameterType.PARAMETER_DOUBLE, double_value=max_vel), |
| 115 | + ), |
| 116 | + ] |
| 117 | + future = set_params_client.call_async(set_params_request) |
| 118 | + rclpy.spin_until_future_complete(self.test_node, future) |
| 119 | + |
| 120 | + if future.result() is None: |
| 121 | + self.test_node.get_logger().error( |
| 122 | + "Exception while calling service: %r" % future.exception() |
| 123 | + ) |
| 124 | + raise self.failureException("setting of initial parameters failed") |
| 125 | + |
| 126 | + @staticmethod |
| 127 | + def make_velocity_limit_msg(vel): |
| 128 | + msg = VelocityLimit() |
| 129 | + msg.use_constraints = False |
| 130 | + msg.max_velocity = vel |
| 131 | + return msg |
| 132 | + |
| 133 | + def test_external_velocity_limit_selector_node(self): |
| 134 | + self.update_max_vel_param(15.0) |
| 135 | + # clear velocity limit to trigger first output |
| 136 | + clear_cmd = VelocityLimitClearCommand(command=True) |
| 137 | + self.pub_clear_limit_.publish(clear_cmd) |
| 138 | + self.wait_for_output() |
| 139 | + # velocity limit is 0 before any limit is set |
| 140 | + self.assertEqual(self.velocity_limit_output_.max_velocity, 0.0) |
| 141 | + |
| 142 | + # Send velocity limits |
| 143 | + # new API velocity limit: higher than the node param -> limit is set to the param value |
| 144 | + api_limit = self.make_velocity_limit_msg(20.0) |
| 145 | + self.pub_api_limit_.publish(api_limit) |
| 146 | + self.wait_for_output() |
| 147 | + self.assertEqual(self.velocity_limit_output_.max_velocity, 15.0) |
| 148 | + # new API velocity limit |
| 149 | + api_limit = self.make_velocity_limit_msg(10.0) |
| 150 | + self.pub_api_limit_.publish(api_limit) |
| 151 | + self.wait_for_output() |
| 152 | + self.assertEqual(self.velocity_limit_output_.max_velocity, 10.0) |
| 153 | + # new INTERNAL velocity limit |
| 154 | + internal_limit = self.make_velocity_limit_msg(5.0) |
| 155 | + self.pub_internal_limit_.publish(internal_limit) |
| 156 | + self.wait_for_output() |
| 157 | + self.assertEqual(self.velocity_limit_output_.max_velocity, 5.0) |
| 158 | + # CLEAR: back to API velocity limit |
| 159 | + self.pub_clear_limit_.publish(clear_cmd) |
| 160 | + self.wait_for_output() |
| 161 | + self.assertEqual(self.velocity_limit_output_.max_velocity, 10.0) |
| 162 | + # lower the max_vel node parameter |
| 163 | + self.update_max_vel_param(2.5) |
| 164 | + self.pub_clear_limit_.publish(clear_cmd) |
| 165 | + self.wait_for_output() |
| 166 | + self.assertEqual(self.velocity_limit_output_.max_velocity, 2.5) |
| 167 | + # velocity limit set by internal limit is no longer applied since above max_vel parameter |
| 168 | + internal_limit = self.make_velocity_limit_msg(5.0) |
| 169 | + self.pub_internal_limit_.publish(internal_limit) |
| 170 | + self.wait_for_output() |
| 171 | + self.assertEqual(self.velocity_limit_output_.max_velocity, 2.5) |
| 172 | + |
| 173 | + |
| 174 | +@launch_testing.post_shutdown_test() |
| 175 | +class TestProcessOutput(unittest.TestCase): |
| 176 | + def test_exit_code(self, proc_info): |
| 177 | + # Check that process exits with code 0: no error |
| 178 | + launch_testing.asserts.assertExitCodes(proc_info) |
0 commit comments