|
12 | 12 | import opengen as og |
13 | 13 |
|
14 | 14 |
|
| 15 | +class BuildConfigurationRos2TestCase(unittest.TestCase): |
| 16 | + """Unit tests for ROS2-specific build configuration behavior.""" |
| 17 | + |
| 18 | + def test_with_ros2_sets_ros2_config_and_enables_c_bindings(self): |
| 19 | + """`with_ros2` should store the ROS2 config and enable C bindings.""" |
| 20 | + ros2_config = og.config.RosConfiguration().with_package_name("unit_test_ros2_pkg") |
| 21 | + build_config = og.config.BuildConfiguration().with_ros2(ros2_config) |
| 22 | + |
| 23 | + self.assertIs(build_config.ros2_config, ros2_config) |
| 24 | + self.assertIsNone(build_config.ros_config) |
| 25 | + self.assertTrue(build_config.build_c_bindings) |
| 26 | + |
| 27 | + build_dict = build_config.to_dict() |
| 28 | + self.assertIn("ros2_config", build_dict) |
| 29 | + self.assertNotIn("ros_config", build_dict) |
| 30 | + self.assertEqual("unit_test_ros2_pkg", build_dict["ros2_config"]["package_name"]) |
| 31 | + |
| 32 | + def test_ros_and_ros2_configs_clear_each_other(self): |
| 33 | + """Selecting ROS1 or ROS2 should clear the other package configuration.""" |
| 34 | + ros1_config = og.config.RosConfiguration().with_package_name("unit_test_ros_pkg") |
| 35 | + ros2_config = og.config.RosConfiguration().with_package_name("unit_test_ros2_pkg") |
| 36 | + build_config = og.config.BuildConfiguration() |
| 37 | + |
| 38 | + build_config.with_ros2(ros2_config) |
| 39 | + self.assertIs(build_config.ros2_config, ros2_config) |
| 40 | + self.assertIsNone(build_config.ros_config) |
| 41 | + |
| 42 | + build_config.with_ros(ros1_config) |
| 43 | + self.assertIs(build_config.ros_config, ros1_config) |
| 44 | + self.assertIsNone(build_config.ros2_config) |
| 45 | + |
| 46 | + build_config.with_ros2(ros2_config) |
| 47 | + self.assertIs(build_config.ros2_config, ros2_config) |
| 48 | + self.assertIsNone(build_config.ros_config) |
| 49 | + |
| 50 | + |
| 51 | +class Ros2TemplateCustomizationTestCase(unittest.TestCase): |
| 52 | + """Generation tests for custom ROS2 configuration values.""" |
| 53 | + |
| 54 | + TEST_DIR = ".python_test_build" |
| 55 | + OPTIMIZER_NAME = "rosenbrock_ros2_custom" |
| 56 | + PACKAGE_NAME = "custom_parametric_optimizer_ros2" |
| 57 | + NODE_NAME = "custom_open_node_ros2" |
| 58 | + DESCRIPTION = "custom ROS2 package for generation tests" |
| 59 | + RESULT_TOPIC = "custom_result_topic" |
| 60 | + PARAMS_TOPIC = "custom_params_topic" |
| 61 | + RATE = 17.5 |
| 62 | + RESULT_QUEUE_SIZE = 11 |
| 63 | + PARAMS_QUEUE_SIZE = 13 |
| 64 | + |
| 65 | + @staticmethod |
| 66 | + def get_open_local_absolute_path(): |
| 67 | + """Return the absolute path to the local OpEn repository root.""" |
| 68 | + cwd = os.getcwd() |
| 69 | + return cwd.split('open-codegen')[0] |
| 70 | + |
| 71 | + @classmethod |
| 72 | + def solverConfig(cls): |
| 73 | + """Return a solver configuration shared by the ROS2 generation tests.""" |
| 74 | + return Ros2BuildTestCase.solverConfig() |
| 75 | + |
| 76 | + @classmethod |
| 77 | + def setUpCustomRos2PackageGeneration(cls): |
| 78 | + """Generate a ROS2 package with non-default configuration values.""" |
| 79 | + u = cs.MX.sym("u", 5) |
| 80 | + p = cs.MX.sym("p", 2) |
| 81 | + phi = og.functions.rosenbrock(u, p) |
| 82 | + c = cs.vertcat(1.5 * u[0] - u[1], |
| 83 | + cs.fmax(0.0, u[2] - u[3] + 0.1)) |
| 84 | + bounds = og.constraints.Ball2(None, 1.5) |
| 85 | + meta = og.config.OptimizerMeta() \ |
| 86 | + .with_optimizer_name(cls.OPTIMIZER_NAME) |
| 87 | + problem = og.builder.Problem(u, p, phi) \ |
| 88 | + .with_constraints(bounds) \ |
| 89 | + .with_penalty_constraints(c) |
| 90 | + ros_config = og.config.RosConfiguration() \ |
| 91 | + .with_package_name(cls.PACKAGE_NAME) \ |
| 92 | + .with_node_name(cls.NODE_NAME) \ |
| 93 | + .with_description(cls.DESCRIPTION) \ |
| 94 | + .with_rate(cls.RATE) \ |
| 95 | + .with_queue_sizes(cls.RESULT_QUEUE_SIZE, cls.PARAMS_QUEUE_SIZE) \ |
| 96 | + .with_publisher_subtopic(cls.RESULT_TOPIC) \ |
| 97 | + .with_subscriber_subtopic(cls.PARAMS_TOPIC) |
| 98 | + build_config = og.config.BuildConfiguration() \ |
| 99 | + .with_open_version(local_path=cls.get_open_local_absolute_path()) \ |
| 100 | + .with_build_directory(cls.TEST_DIR) \ |
| 101 | + .with_build_mode(og.config.BuildConfiguration.DEBUG_MODE) \ |
| 102 | + .with_build_c_bindings() \ |
| 103 | + .with_ros2(ros_config) |
| 104 | + og.builder.OpEnOptimizerBuilder(problem, |
| 105 | + metadata=meta, |
| 106 | + build_configuration=build_config, |
| 107 | + solver_configuration=cls.solverConfig()) \ |
| 108 | + .build() |
| 109 | + |
| 110 | + @classmethod |
| 111 | + def setUpClass(cls): |
| 112 | + """Generate the custom ROS2 package once before running tests.""" |
| 113 | + cls.setUpCustomRos2PackageGeneration() |
| 114 | + |
| 115 | + @classmethod |
| 116 | + def ros2_package_dir(cls): |
| 117 | + """Return the filesystem path to the generated custom ROS2 package.""" |
| 118 | + return os.path.join( |
| 119 | + cls.TEST_DIR, |
| 120 | + cls.OPTIMIZER_NAME, |
| 121 | + cls.PACKAGE_NAME) |
| 122 | + |
| 123 | + def test_custom_ros2_configuration_is_rendered_into_generated_files(self): |
| 124 | + """Custom ROS2 config values should appear in the generated package files.""" |
| 125 | + ros2_dir = self.ros2_package_dir() |
| 126 | + |
| 127 | + with open(os.path.join(ros2_dir, "package.xml"), encoding="utf-8") as f: |
| 128 | + package_xml = f.read() |
| 129 | + self.assertIn(f"<name>{self.PACKAGE_NAME}</name>", package_xml) |
| 130 | + self.assertIn(f"<description>{self.DESCRIPTION}</description>", package_xml) |
| 131 | + |
| 132 | + with open(os.path.join(ros2_dir, "include", "open_optimizer.hpp"), encoding="utf-8") as f: |
| 133 | + optimizer_header = f.read() |
| 134 | + self.assertIn(f'#define ROS2_NODE_{self.OPTIMIZER_NAME.upper()}_NODE_NAME "{self.NODE_NAME}"', |
| 135 | + optimizer_header) |
| 136 | + self.assertIn(f'#define ROS2_NODE_{self.OPTIMIZER_NAME.upper()}_RESULT_TOPIC "{self.RESULT_TOPIC}"', |
| 137 | + optimizer_header) |
| 138 | + self.assertIn(f'#define ROS2_NODE_{self.OPTIMIZER_NAME.upper()}_PARAMS_TOPIC "{self.PARAMS_TOPIC}"', |
| 139 | + optimizer_header) |
| 140 | + self.assertIn(f"#define ROS2_NODE_{self.OPTIMIZER_NAME.upper()}_RATE {self.RATE}", |
| 141 | + optimizer_header) |
| 142 | + self.assertIn( |
| 143 | + f"#define ROS2_NODE_{self.OPTIMIZER_NAME.upper()}_RESULT_TOPIC_QUEUE_SIZE {self.RESULT_QUEUE_SIZE}", |
| 144 | + optimizer_header) |
| 145 | + self.assertIn( |
| 146 | + f"#define ROS2_NODE_{self.OPTIMIZER_NAME.upper()}_PARAMS_TOPIC_QUEUE_SIZE {self.PARAMS_QUEUE_SIZE}", |
| 147 | + optimizer_header) |
| 148 | + |
| 149 | + with open(os.path.join(ros2_dir, "config", "open_params.yaml"), encoding="utf-8") as f: |
| 150 | + params_yaml = f.read() |
| 151 | + self.assertIn(f'result_topic: "{self.RESULT_TOPIC}"', params_yaml) |
| 152 | + self.assertIn(f'params_topic: "{self.PARAMS_TOPIC}"', params_yaml) |
| 153 | + self.assertIn(f"rate: {self.RATE}", params_yaml) |
| 154 | + |
| 155 | + with open(os.path.join(ros2_dir, "launch", "open_optimizer.launch.py"), encoding="utf-8") as f: |
| 156 | + launch_file = f.read() |
| 157 | + self.assertIn(f'package="{self.PACKAGE_NAME}"', launch_file) |
| 158 | + self.assertIn(f'executable="{self.NODE_NAME}"', launch_file) |
| 159 | + self.assertIn(f'name="{self.NODE_NAME}"', launch_file) |
| 160 | + self.assertIn(f'FindPackageShare("{self.PACKAGE_NAME}")', launch_file) |
| 161 | + |
| 162 | + |
15 | 163 | class Ros2BuildTestCase(unittest.TestCase): |
16 | 164 | """Integration tests for auto-generated ROS2 packages.""" |
17 | 165 |
|
|
0 commit comments