diff --git a/common/autoware_test_utils/include/autoware_test_utils/mock_data_parser.hpp b/common/autoware_test_utils/include/autoware_test_utils/mock_data_parser.hpp index 714d6d6710b32..8fc71cf95e1ac 100644 --- a/common/autoware_test_utils/include/autoware_test_utils/mock_data_parser.hpp +++ b/common/autoware_test_utils/include/autoware_test_utils/mock_data_parser.hpp @@ -16,9 +16,11 @@ #define AUTOWARE_TEST_UTILS__MOCK_DATA_PARSER_HPP_ #include +#include #include #include +#include #include #include #include @@ -36,16 +38,22 @@ namespace autoware::test_utils { +using autoware_adapi_v1_msgs::msg::OperationModeState; using autoware_perception_msgs::msg::ObjectClassification; using autoware_perception_msgs::msg::PredictedObject; using autoware_perception_msgs::msg::PredictedObjectKinematics; using autoware_perception_msgs::msg::PredictedObjects; using autoware_perception_msgs::msg::PredictedPath; using autoware_perception_msgs::msg::Shape; +using autoware_perception_msgs::msg::TrafficLightElement; +using autoware_perception_msgs::msg::TrafficLightGroup; +using autoware_perception_msgs::msg::TrafficLightGroupArray; + using autoware_planning_msgs::msg::LaneletPrimitive; using autoware_planning_msgs::msg::LaneletRoute; using autoware_planning_msgs::msg::LaneletSegment; using builtin_interfaces::msg::Duration; +using builtin_interfaces::msg::Time; using geometry_msgs::msg::Accel; using geometry_msgs::msg::AccelWithCovariance; using geometry_msgs::msg::AccelWithCovarianceStamped; @@ -79,6 +87,9 @@ Header parse(const YAML::Node & node); template <> Duration parse(const YAML::Node & node); +template <> +Time parse(const YAML::Node & node); + template <> std::vector parse(const YAML::Node & node); @@ -142,6 +153,18 @@ PredictedObject parse(const YAML::Node & node); template <> PredictedObjects parse(const YAML::Node & node); +template <> +TrafficLightGroupArray parse(const YAML::Node & node); + +template <> +TrafficLightGroup parse(const YAML::Node & node); + +template <> +TrafficLightElement parse(const YAML::Node & node); + +template <> +OperationModeState parse(const YAML::Node & node); + /** * @brief Parses a YAML file and converts it into an object of type T. * diff --git a/common/autoware_test_utils/src/mock_data_parser.cpp b/common/autoware_test_utils/src/mock_data_parser.cpp index b876f1312a3e6..d2c6de5c0a46f 100644 --- a/common/autoware_test_utils/src/mock_data_parser.cpp +++ b/common/autoware_test_utils/src/mock_data_parser.cpp @@ -44,6 +44,15 @@ Duration parse(const YAML::Node & node) return msg; } +template <> +Time parse(const YAML::Node & node) +{ + Time msg; + msg.sec = node["sec"].as(); + msg.nanosec = node["nanosec"].as(); + return msg; +} + template <> std::array parse(const YAML::Node & node) { @@ -321,6 +330,54 @@ PredictedObjects parse(const YAML::Node & node) return msg; } +template <> +TrafficLightElement parse(const YAML::Node & node) +{ + TrafficLightElement msg; + msg.color = node["color"].as(); + msg.shape = node["shape"].as(); + msg.status = node["status"].as(); + msg.confidence = node["confidence"].as(); + return msg; +} + +template <> +TrafficLightGroup parse(const YAML::Node & node) +{ + TrafficLightGroup msg; + msg.traffic_light_group_id = node["traffic_light_group_id"].as(); + for (const auto & element_node : node["elements"]) { + msg.elements.push_back(parse(element_node)); + } + return msg; +} + +template <> +TrafficLightGroupArray parse(const YAML::Node & node) +{ + TrafficLightGroupArray msg; + msg.stamp = parse