From 8881d23d1bb666a8fab913e7c30e60b9b4a2b5b5 Mon Sep 17 00:00:00 2001 From: badai nguyen <94814556+badai-nguyen@users.noreply.github.com> Date: Wed, 24 Apr 2024 10:16:42 +0900 Subject: [PATCH 01/18] chore(roi_pointcloud_fusion): add maximum cluster size param (#6860) Signed-off-by: badai-nguyen --- .../config/roi_pointcloud_fusion.param.yaml | 1 + .../docs/roi-pointcloud-fusion.md | 1 + .../roi_pointcloud_fusion/node.hpp | 1 + .../include/image_projection_based_fusion/utils/utils.hpp | 4 ++-- .../schema/roi_pointcloud_fusion.schema.json | 5 +++++ .../src/roi_pointcloud_fusion/node.cpp | 7 +++++-- .../image_projection_based_fusion/src/utils/utils.cpp | 8 +++++--- 7 files changed, 20 insertions(+), 7 deletions(-) diff --git a/perception/image_projection_based_fusion/config/roi_pointcloud_fusion.param.yaml b/perception/image_projection_based_fusion/config/roi_pointcloud_fusion.param.yaml index 5b86b8e81d1aa..acf5f75163ffe 100644 --- a/perception/image_projection_based_fusion/config/roi_pointcloud_fusion.param.yaml +++ b/perception/image_projection_based_fusion/config/roi_pointcloud_fusion.param.yaml @@ -2,4 +2,5 @@ ros__parameters: fuse_unknown_only: true min_cluster_size: 2 + max_cluster_size: 20 cluster_2d_tolerance: 0.5 diff --git a/perception/image_projection_based_fusion/docs/roi-pointcloud-fusion.md b/perception/image_projection_based_fusion/docs/roi-pointcloud-fusion.md index 5d0b241a578d6..f2ce7662da976 100644 --- a/perception/image_projection_based_fusion/docs/roi-pointcloud-fusion.md +++ b/perception/image_projection_based_fusion/docs/roi-pointcloud-fusion.md @@ -37,6 +37,7 @@ The node `roi_pointcloud_fusion` is to cluster the pointcloud based on Region Of | Name | Type | Description | | ---------------------- | ------ | -------------------------------------------------------------------------------------------- | | `min_cluster_size` | int | the minimum number of points that a cluster needs to contain in order to be considered valid | +| `max_cluster_size` | int | the maximum number of points that a cluster needs to contain in order to be considered valid | | `cluster_2d_tolerance` | double | cluster tolerance measured in radial direction | | `rois_number` | int | the number of input rois | diff --git a/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_pointcloud_fusion/node.hpp b/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_pointcloud_fusion/node.hpp index fe685baa0b6e2..4cbc0990352e6 100644 --- a/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_pointcloud_fusion/node.hpp +++ b/perception/image_projection_based_fusion/include/image_projection_based_fusion/roi_pointcloud_fusion/node.hpp @@ -26,6 +26,7 @@ class RoiPointCloudFusionNode { private: int min_cluster_size_{1}; + int max_cluster_size_{20}; bool fuse_unknown_only_{true}; double cluster_2d_tolerance_; diff --git a/perception/image_projection_based_fusion/include/image_projection_based_fusion/utils/utils.hpp b/perception/image_projection_based_fusion/include/image_projection_based_fusion/utils/utils.hpp index d7fd3c3882046..943f028621189 100644 --- a/perception/image_projection_based_fusion/include/image_projection_based_fusion/utils/utils.hpp +++ b/perception/image_projection_based_fusion/include/image_projection_based_fusion/utils/utils.hpp @@ -70,8 +70,8 @@ PointCloud closest_cluster( void updateOutputFusedObjects( std::vector & output_objs, const std::vector & clusters, const std_msgs::msg::Header & in_cloud_header, const std_msgs::msg::Header & in_roi_header, - const tf2_ros::Buffer & tf_buffer, const int min_cluster_size, const float cluster_2d_tolerance, - std::vector & output_fused_objects); + const tf2_ros::Buffer & tf_buffer, const int min_cluster_size, const int max_cluster_size, + const float cluster_2d_tolerance, std::vector & output_fused_objects); geometry_msgs::msg::Point getCentroid(const sensor_msgs::msg::PointCloud2 & pointcloud); diff --git a/perception/image_projection_based_fusion/schema/roi_pointcloud_fusion.schema.json b/perception/image_projection_based_fusion/schema/roi_pointcloud_fusion.schema.json index f39ef257ea789..9dba97a2029ee 100644 --- a/perception/image_projection_based_fusion/schema/roi_pointcloud_fusion.schema.json +++ b/perception/image_projection_based_fusion/schema/roi_pointcloud_fusion.schema.json @@ -16,6 +16,11 @@ "description": "The minimum number of points that a cluster must contain to be considered as valid.", "default": 2 }, + "max_cluster_size": { + "type": "integer", + "description": "The maximum number of points that a cluster must contain to be considered as valid.", + "default": 20 + }, "cluster_2d_tolerance": { "type": "number", "description": "A cluster tolerance measured in radial direction [m]", diff --git a/perception/image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp b/perception/image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp index 421aa3a453451..af04d174ba661 100644 --- a/perception/image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp +++ b/perception/image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp @@ -35,6 +35,7 @@ RoiPointCloudFusionNode::RoiPointCloudFusionNode(const rclcpp::NodeOptions & opt { fuse_unknown_only_ = declare_parameter("fuse_unknown_only"); min_cluster_size_ = declare_parameter("min_cluster_size"); + max_cluster_size_ = declare_parameter("max_cluster_size"); cluster_2d_tolerance_ = declare_parameter("cluster_2d_tolerance"); pub_objects_ptr_ = this->create_publisher("output_clusters", rclcpp::QoS{1}); @@ -138,7 +139,9 @@ void RoiPointCloudFusionNode::fuseOnSingleImage( auto & feature_obj = output_objs.at(i); const auto & check_roi = feature_obj.feature.roi; auto & cluster = clusters.at(i); - + if (cluster.points.size() >= static_cast(max_cluster_size_)) { + continue; + } if ( check_roi.x_offset <= normalized_projected_point.x() && check_roi.y_offset <= normalized_projected_point.y() && @@ -152,7 +155,7 @@ void RoiPointCloudFusionNode::fuseOnSingleImage( // refine and update output_fused_objects_ updateOutputFusedObjects( output_objs, clusters, input_pointcloud_msg.header, input_roi_msg.header, tf_buffer_, - min_cluster_size_, cluster_2d_tolerance_, output_fused_objects_); + min_cluster_size_, max_cluster_size_, cluster_2d_tolerance_, output_fused_objects_); } bool RoiPointCloudFusionNode::out_of_scope(__attribute__((unused)) diff --git a/perception/image_projection_based_fusion/src/utils/utils.cpp b/perception/image_projection_based_fusion/src/utils/utils.cpp index 76cd1e3c61e82..e978b5ab55868 100644 --- a/perception/image_projection_based_fusion/src/utils/utils.cpp +++ b/perception/image_projection_based_fusion/src/utils/utils.cpp @@ -83,8 +83,8 @@ PointCloud closest_cluster( void updateOutputFusedObjects( std::vector & output_objs, const std::vector & clusters, const std_msgs::msg::Header & in_cloud_header, const std_msgs::msg::Header & in_roi_header, - const tf2_ros::Buffer & tf_buffer, const int min_cluster_size, const float cluster_2d_tolerance, - std::vector & output_fused_objects) + const tf2_ros::Buffer & tf_buffer, const int min_cluster_size, const int max_cluster_size, + const float cluster_2d_tolerance, std::vector & output_fused_objects) { if (output_objs.size() != clusters.size()) { return; @@ -107,7 +107,9 @@ void updateOutputFusedObjects( for (std::size_t i = 0; i < output_objs.size(); ++i) { PointCloud cluster = clusters.at(i); auto & feature_obj = output_objs.at(i); - if (cluster.points.size() < std::size_t(min_cluster_size)) { + if ( + cluster.points.size() < std::size_t(min_cluster_size) || + cluster.points.size() >= std::size_t(max_cluster_size)) { continue; } From 645981641a3d12b2d3cd93d6a083bee846aa9513 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 24 Apr 2024 11:51:45 +0900 Subject: [PATCH 02/18] feat(perception_evaluator): counts objects within detection range (#6848) * feat(perception_evaluator): counts objects within detection range Signed-off-by: kosuke55 detection counter Signed-off-by: kosuke55 add enable option and refactoring Signed-off-by: kosuke55 fix update document Signed-off-by: kosuke55 readme Signed-off-by: kosuke55 clean up Signed-off-by: kosuke55 * fix from review Signed-off-by: kosuke55 * use $ Signed-off-by: kosuke55 fix Signed-off-by: kosuke55 * fix include Signed-off-by: kosuke55 --------- Signed-off-by: kosuke55 --- .../CMakeLists.txt | 3 +- .../perception_online_evaluator/README.md | 90 +++- .../images/detection_counts.drawio.svg | 445 ++++++++++++++++++ .../images/yaw_rate.drawio.svg | 172 ++++++- .../metrics/detection_count.hpp | 149 ++++++ .../metrics/metric.hpp | 10 +- .../metrics_calculator.hpp | 19 +- .../parameters.hpp | 12 +- .../perception_online_evaluator_node.hpp | 1 + .../perception_online_evaluator.defaults.yaml | 70 ++- .../src/metrics/detection_count.cpp | 234 +++++++++ .../src/metrics_calculator.cpp | 137 ++++-- .../src/perception_online_evaluator_node.cpp | 98 ++-- .../src/utils/objects_filtering.cpp | 44 -- .../test_perception_online_evaluator_node.cpp | 404 +++++++++++++++- 15 files changed, 1697 insertions(+), 191 deletions(-) create mode 100644 evaluator/perception_online_evaluator/images/detection_counts.drawio.svg create mode 100644 evaluator/perception_online_evaluator/include/perception_online_evaluator/metrics/detection_count.hpp create mode 100644 evaluator/perception_online_evaluator/src/metrics/detection_count.cpp diff --git a/evaluator/perception_online_evaluator/CMakeLists.txt b/evaluator/perception_online_evaluator/CMakeLists.txt index e1cd0546ea94a..3d967ea6d86ce 100644 --- a/evaluator/perception_online_evaluator/CMakeLists.txt +++ b/evaluator/perception_online_evaluator/CMakeLists.txt @@ -12,6 +12,7 @@ ament_auto_add_library(${PROJECT_NAME}_node SHARED src/metrics_calculator.cpp src/${PROJECT_NAME}_node.cpp src/metrics/deviation_metrics.cpp + src/metrics/detection_count.cpp src/utils/marker_utils.cpp src/utils/objects_filtering.cpp ) @@ -31,7 +32,7 @@ target_link_libraries(${PROJECT_NAME}_node glog::glog) if(BUILD_TESTING) ament_add_ros_isolated_gtest(test_${PROJECT_NAME} test/test_perception_online_evaluator_node.cpp - TIMEOUT 180 + TIMEOUT 300 ) target_link_libraries(test_${PROJECT_NAME} ${PROJECT_NAME}_node diff --git a/evaluator/perception_online_evaluator/README.md b/evaluator/perception_online_evaluator/README.md index fd8aee9766308..7ee93d2ffddf2 100644 --- a/evaluator/perception_online_evaluator/README.md +++ b/evaluator/perception_online_evaluator/README.md @@ -15,6 +15,9 @@ The evaluated metrics are as follows: - lateral_deviation - yaw_deviation - yaw_rate +- total_objects_count +- average_objects_count +- interval_objects_count ### Predicted Path Deviation / Predicted Path Deviation Variance @@ -89,6 +92,67 @@ Calculates the yaw rate of an object based on the change in yaw angle from the p ![yaw_rate](./images/yaw_rate.drawio.svg) +### Object Counts + +Counts the number of detections for each object class within the specified detection range. These metrics are measured for the most recent object not past objects. + +![detection_counts](./images/detection_counts.drawio.svg) + +In the provided illustration, the range $R$ is determined by a combination of lists of radii (e.g., $r_1, r_2, \ldots$) and heights (e.g., $h_1, h_2, \ldots$). +For example, + +- the number of CAR in range $R = (r_1, h_1)$ equals 1 +- the number of CAR in range $R = (r_1, h_2)$ equals 2 +- the number of CAR in range $R = (r_2, h_1)$ equals 3 +- the number of CAR in range $R = (r_2, h_2)$ equals 4 + +#### Total Object Count + +Counts the number of unique objects for each class within the specified detection range. The total object count is calculated as follows: + +$$ +\begin{align} +\text{Total Object Count (Class, Range)} = \left| \bigcup_{t=0}^{T_{\text{now}}} \{ \text{uuid} \mid \text{class}(t, \text{uuid}) = C \wedge \text{position}(t, \text{uuid}) \in R \} \right| +\end{align} +$$ + +where: + +- $\bigcup$ represents the union across all frames from $t = 0$ to $T_{\text{now}}$, which ensures that each uuid is counted only once. +- $\text{class}(t, \text{uuid}) = C$ specifies that the object with uuid at time $t$ belongs to class $C$. +- $\text{position}(t, \text{uuid}) \in R$ indicates that the object with uuid at time $t$ is within the specified range $R$. +- $\left| \{ \ldots \} \right|$ denotes the cardinality of the set, which counts the number of unique uuids that meet the class and range criteria across all considered times. + +#### Average Object Count + +Counts the average number of objects for each class within the specified detection range. This metric measures how many objects were detected in one frame, without considering uuids. The average object count is calculated as follows: + +$$ +\begin{align} +\text{Average Object Count (Class, Range)} = \frac{1}{N} \sum_{t=0}^{T_{\text{now}}} \left| \{ \text{object} \mid \text{class}(t, \text{object}) = C \wedge \text{position}(t, \text{object}) \in R \} \right| +\end{align} +$$ + +where: + +- $N$ represents the total number of frames within the time period time to $T\_{\text{now}}$ (it is precisely `detection_count_purge_seconds`) +- $text{object}$ denotes the number of objects that meet the class and range criteria at time $t$. + +#### Interval Object Count + +Counts the average number of objects for each class within the specified detection range over the last `objects_count_window_seconds`. This metric measures how many objects were detected in one frame, without considering uuids. The interval object count is calculated as follows: + +$$ +\begin{align} +\text{Interval Object Count (Class, Range)} = \frac{1}{W} \sum_{t=T_{\text{now}} - T_W}^{T_{\text{now}}} \left| \{ \text{object} \mid \text{class}(t, \text{object}) = C \wedge \text{position}(t, \text{object}) \in R \} \right| +\end{align} +$$ + +where: + +- $W$ represents the total number of frames within the last `objects_count_window_seconds`. +- $T_W$ represents the time window `objects_count_window_seconds` + ## Inputs / Outputs | Name | Type | Description | @@ -99,14 +163,24 @@ Calculates the yaw rate of an object based on the change in yaw angle from the p ## Parameters -| Name | Type | Description | -| --------------------------------- | ------------ | ------------------------------------------------------------------------------------------------ | -| `selected_metrics` | List | Metrics to be evaluated, such as lateral deviation, yaw deviation, and predicted path deviation. | -| `smoothing_window_size` | Integer | Determines the window size for smoothing path, should be an odd number. | -| `prediction_time_horizons` | list[double] | Time horizons for prediction evaluation in seconds. | -| `stopped_velocity_threshold` | double | threshold velocity to check if vehicle is stopped | -| `target_object.*.check_deviation` | bool | Whether to check deviation for specific object types (car, truck, etc.). | -| `debug_marker.*` | bool | Debugging parameters for marker visualization (history path, predicted path, etc.). | +| Name | Type | Description | +| ------------------------------------------------------ | ------------ | ----------------------------------------------------------------------------------------------------------------------------------------------- | +| `selected_metrics` | List | Metrics to be evaluated, such as lateral deviation, yaw deviation, and predicted path deviation. | +| `smoothing_window_size` | Integer | Determines the window size for smoothing path, should be an odd number. | +| `prediction_time_horizons` | list[double] | Time horizons for prediction evaluation in seconds. | +| `stopped_velocity_threshold` | double | threshold velocity to check if vehicle is stopped | +| `detection_radius_list` | list[double] | Detection radius for objects to be evaluated.(used for objects count only) | +| `detection_height_list` | list[double] | Detection height for objects to be evaluated. (used for objects count only) | +| `detection_count_purge_seconds` | double | Time window for purging object detection counts. | +| `objects_count_window_seconds` | double | Time window for keeping object detection counts. The number of object detections within this time window is stored in `detection_count_vector_` | +| `target_object.*.check_lateral_deviation` | bool | Whether to check lateral deviation for specific object types (car, truck, etc.). | +| `target_object.*.check_yaw_deviation` | bool | Whether to check yaw deviation for specific object types (car, truck, etc.). | +| `target_object.*.check_predicted_path_deviation` | bool | Whether to check predicted path deviation for specific object types (car, truck, etc.). | +| `target_object.*.check_yaw_rate` | bool | Whether to check yaw rate for specific object types (car, truck, etc.). | +| `target_object.*.check_total_objects_count` | bool | Whether to check total object count for specific object types (car, truck, etc.). | +| `target_object.*.check_average_objects_count` | bool | Whether to check average object count for specific object types (car, truck, etc.). | +| `target_object.*.check_interval_average_objects_count` | bool | Whether to check interval average object count for specific object types (car, truck, etc.). | +| `debug_marker.*` | bool | Debugging parameters for marker visualization (history path, predicted path, etc.). | ## Assumptions / Known limits diff --git a/evaluator/perception_online_evaluator/images/detection_counts.drawio.svg b/evaluator/perception_online_evaluator/images/detection_counts.drawio.svg new file mode 100644 index 0000000000000..f6dc7431e7ae6 --- /dev/null +++ b/evaluator/perception_online_evaluator/images/detection_counts.drawio.svg @@ -0,0 +1,445 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ + + + + + + + + + + + + + + + + + + + + + +
+
+
+
+ `r_2` +
+
+
+ + + + + + + +
+
+
+ + + + + + + + + + + + + + + + + + + + + + +
+
+
+
+ `r_1` +
+
+
+ + + + + + + + + + + + + + + + + +
+
+
+ + + + + + + + + + + + + + + + + + + + + + +
+
+
+
+ `h_1` +
+
+
+ + + + + + + +
+
+
+ + + + + + + + + + + + + + + + + + + + + + +
+
+
+
+ `h_2` +
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
diff --git a/evaluator/perception_online_evaluator/images/yaw_rate.drawio.svg b/evaluator/perception_online_evaluator/images/yaw_rate.drawio.svg index 20587ec30d683..eeabd7dca8d43 100644 --- a/evaluator/perception_online_evaluator/images/yaw_rate.drawio.svg +++ b/evaluator/perception_online_evaluator/images/yaw_rate.drawio.svg @@ -5,10 +5,10 @@ xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" version="1.1" - width="283px" + width="365px" height="77px" - viewBox="-0.5 -0.5 283 77" - content="<mxfile host="app.diagrams.net" modified="2024-04-15T16:43:48.109Z" agent="Mozilla/5.0 (X11; Linux x86_64) AppleWebKit/537.36 (KHTML, like Gecko) Chrome/122.0.0.0 Safari/537.36" version="24.2.5" etag="-1Cxl0cC8cre4wtqPdY1" type="google" scale="1" border="0"> <diagram name="ページ1" id="hj15VFmwux7EVVTqehov"> <mxGraphModel dx="-203" dy="1514" grid="1" gridSize="10" guides="1" tooltips="1" connect="1" arrows="1" fold="0" page="1" pageScale="1" pageWidth="827" pageHeight="1169" math="1" shadow="0"> <root> <mxCell id="0" /> <mxCell id="1" parent="0" /> <mxCell id="2" value="" style="shape=image;verticalLabelPosition=bottom;labelBackgroundColor=default;verticalAlign=top;aspect=fixed;imageAspect=0;image=data:image/svg+xml,PHN2ZyB4bWxuczp4bGluaz0iaHR0cDovL3d3dy53My5vcmcvMTk5OS94bGluayIgeG1sbnM9Imh0dHA6Ly93d3cudzMub3JnLzIwMDAvc3ZnIiB4bWw6c3BhY2U9InByZXNlcnZlIiBzdHJva2UtbGluZWpvaW49InJvdW5kIiBzdHJva2Utd2lkdGg9IjI4LjIyMiIgdmVyc2lvbj0iMS4xIiB2aWV3Qm94PSIwIDAgMjAwIDEwMCIgaGVpZ2h0PSIxbW0iIHdpZHRoPSIybW0iPiYjeGE7IDxpbWFnZSB4bGluazpocmVmPSJkYXRhOmltYWdlL3BuZztiYXNlNjQsaVZCT1J3MEtHZ29BQUFBTlNVaEVVZ0FBQU1BQUFBQlVDQVlBQUFEVUt6aFNBQUFKckVsRVFWUjRuTzJkUFc3YlNoREhKNEQ3cUV1UndpcUM0SFZXL3dyekFnL1JEY3diV0Rjd0RRU3ZWazRRK2dSUmx6SjBFYVJsdW9kVWNwZDBTaTdnTnlNT3BlV1lsUGl4S3k3TitRRVRaaWw1ZHlYTmZ6OW1KUExzOGZFUmJQTFgyN2N6UEFSb2RKeXluVnR0UkJrTEQyaHJ0aFF0K2UvSGo5Um1BMmMyS2tHbm4rTWh0NWMyNmxRVXlBWk9za3UwS3pxQnZ2WWJEeXN5Rk1PcWF3T2RCSUNkQ2ZFUWdZN3d5dW1nQVpiRWNJWCtSek5FQkprWU5tMHFheVVBZFh6RkU4ai9QcUpGNkpNUmlpQnVXa0VqQVdBalV6eFFJNWRIbm5xUGxyQnRiSy9ibEhHQS9oYndmd08yS3IvYkNvRUg1aEQ5YlYyM2pkb0M0TXFYVUwzR0o2ZVBvY04wcENnbTZFY0ovM2Q3UkIrY1FMYlBES0ZjREhRdXhlY3Q2czRHdFFTQUZTN3hjRjN4OEIxYTFFUjFpdElHSGxoak1sNk5STUNiWXdNYW9HazJtT0h6RjhmcVBDb0FyQ2d1YVlUNGpyWXdWS29vSjRNSDNKRDljNGwySVo1eVRUTUdQaTg4Vk05QkFSeHcvbHVzT0tyWDFYN1J2TVJKeWVQMmY5QytvWDEydmYvakFYaEdtMkE4M29pSEtWSUVoMFJRS1FCZTlram5weGhzYUNQKzZoTE5TL1JHSHJjbi9rSDcxM2JjdmdvYWtMR3RGTElsa3ZtWmt3ZzJWY3VoVWdId2hsZXUrZW1GQkQ1SGRMamY3OUZlOTl3VlpZL1Z1UDBoU0dBY09VcWdLQUphRHFWbEcrTW5BdUROeFZLYzl0cjVOUzh4R0RySDdZOUJQbG9oZ2lXZVQyU3dwbXdHaU9IcHNpSDAwZmtiNUNVa2VaNGloZXo3SlJ1TDNXb0Z2cGJDbDdLd1R5LzY2a3NPdjc4QlpFdkpkdzMvZklNMnFYaXNkZHkrRGl3Q3F2dVRjWnA4T29iczlld29DSUQvU0RyVHJZOXIvaHA1aVVOY2d2RTZlV3BPd05FWHJvWUN4OWtEdzJSazVSQzd0VDd3b09JaWJsOFhYZzdkUW5GamZFbCtZN2ExRXdCM05oTDFmUGN4Mm5Na0wvRVY3U2ZhRzZqL0FkS0lkQVg3TDF6Undad2wxczlSRkx4VW1Cbld4T0VKQ29XdklGdlRwL0pCRjNIN0p2REdlQTdGMXhWeG43YVlNd0E5VWE2aHJYYklCazN5RWl6cUdSeFBwWmNoWjRtOGpRMXdaaEl5Y1d6NC8ydWZrb0VjL3Axd2NWcGliZlpMK1NpZlFNT05ySzI0ZlFzV2FGK004cms1QzVnQ2lNUWYzdm1XNUdxYWwrQVBLSUc5dzhxOEFCMmJPRUwrb1pVS2lVVmlCYmtuNkJFU2ZRS1p3eWRkSytzYXQyL1RIdFpKMzFZdy9ZYmFqdWsvV3dId05DRWRJYkxWQ1J2WXlrdndWSjBhOVU2Z0tJaW1HK3JuUnI0ZjJwcXJXYTF0M0w0bEVSUjloMmFCT2ZsTlBnUE14Ui9jZXphZGgrQW9MOEd6eElvdGIyOEd4Ylh4Y3hWRm5ybE5vSWVJV0p1NGZjdDIxbGdmN2VuTXozR09WaWtBS3czYm9JKzhoSndsdUI4VEtINmR3aXo3bUgvNGhmYktLSk96eDhETFFWK1d0MDNqOWgySTRha0E0SXhIdTBJbzBVV0NvZ014ZUpDWE1QWVRCVXJXc2w1OFQ0cWR5dHo4clgzb1Z4bE40dllkV0VHV2hOdlZUNzUvVnRMQXZhVUdPek9rdklUU2picHgrdzcxYjBxV1FRRUpZQ2FlbTNSdHpBWkR5a3NvZHFnVHQrOUlBa1VCYkdlQWFjbVRmR0FPQThoTEtOWlp3SUc0ZlVjU0tNNHcweklCK0VJa3l0N2xKUlQ3SEl2YmQyUWp5bHNCRkVaWkg1eHNDSGtKeFNrUlZNVHR1MVRLbTIzejFMbVZDMk01WUM3S1h1VWxGTGNjaXR2YmJtc29Bb2g3NklQU0x6R1V4TzF0NDUwQUJwQ1hVRTdEQ2tyaTlsNWVHOVF5Z1NoN2s1ZFFUa2RWM0I1RWhyNHJQZ3BnSnNwSkQzMVEvQ0FCRWJlMzNZQ1BBcGlLY3RKREh4US9TRURFN1cwM01BUUJLT05sSThwVDJ3MzRLQUR2OGhKS1A1VEY3VzIzNGFNQUZPVmtxQUNVVWFNQ1VFYU5Da0FaTlNvQVpkU29BSlJSb3dKUVJvMEtRQmsxS2dCbDFLZ0FsRkdqQWxCR2pRcEFHVFVxQUdYVXFBQ1VVYU1DVUVhTkNrQVpOU29BWmRUNEtBQzZqdjN1bHo4dUxvV2hEQU8reEx2SmcrMDJmQlRBR29vL2ZadjAwdzNGUTlhMksvUlZBUEphTUVrZkhWRjZKeERsdGUwR2ZCUkFDc1VMb3diOWRFUHhnRUNVVTlzTitDaUFSSlF2K2Y2eG14NzZvdlFFM3lCRjNoMG9zZDJPZHdMZ1MySFFUZkRNNjRQT1FTK1FPemJtb3Z6YlJUREVPd0V3S3lndWcwSlFBWXlOVUpSWExob1ppZ0JvR1RUVmV3U01BNzQxcmx6K3JGeTBSUUx3THU3T2R3d3M5QXV5dTRhRXZYUklPVFdSS0QvWXVETm9XVjZCQkxBR1ArUHVFUlN2RDMrRkx5RFdTeVUrYjloSnI4VHB5RkZ6NjF3QTNzWGQ2YVlZZkJOcVU1eExjSENKYk1VcmxxTDhZUEVHS1lFb2J3V1Fncjl4OXdpS3M4QUZpVUx2RmZ3ODRRSHZRcHlPTERZUmlISktBa2pFU1cvaTdqd0xoRkNjb1c3d1hLcDNpMzllOEoxQmI4VHBlMXVqZjFWZTRXd0FjZmNRc2xuSzdCOEpJempsWnAzZndCbGsxNmduTThzbUpGRDVRZmJCTDFHZThnaWJVTUdudlJUZkZ5NFdwOGtuUTR2TnpHWDk1RDk1R0hRRm5zYmQrWmFaQ3hBM1RFTkxYSW1BUHhEVDVNZ3hCRjZKTXUybGJ0aUFyN3RQa2JZMVpLSkk2WGpxbVovZmEyci9wWGhvWVRuc0hZcnlpdjZwRW9CWGNYZGVDczN3djlmRzZWd0VZWmZsRUkvc0FXU09Uc2NoT250Ynp0bDJyNW5EejBsdUxuMkFsejB4UEhYK0R6YnZESG9vcjdBVndCRGk3dGpIQlR1cktWUjY0ejdoK2R1NkcyTVdVZ0I3aDdkKzE1R0JRKy9IRlJ1OVg5OGhFOFBLNXJLSmwyTmxTOFU3K3F4dHRjTkVvcnpMSzV5Skoza2RkOGUraER4MXl6anhEWThtQzdPL3hybzlBRHVqT3puREJ2YUJneFQyOTdGYWR4a3RzYStQWmhucmV0RzJMcTV2QnZ1Y3psUVlQU1pIM1NvdTJLNTVyN2lDdlNBMkxmb1ZRQmJxbE5FZWdwdy9iRnBuamZZcTh3bzdBUXdsN3M0aTJFQnhPVVRRRy9vRkgvdUt4NTlvYjZEOFRhNEwzYU0yZ2N6SjEzMW54NXRTcDcvc0hEUERqcjFmSkpwOGR2aklzOE1LTWpFY2JJK1hJUkU4ZGNhY0R3NUdmbUlweW9XOGd2d3VVQVFEaUx2emNpaUY3TVhKa2V6dkZsWG02MTZxTXhtYXM3ZUZaOHNrTHh2N29keU9DU0tmSFc2TTJZRXM0UnRkVTMxenlKYlNWYk12L2QzQzVwby9wMDVlb1NDQUljWGR1YThKWkp1b3Brc2JjM1EvZWVURFYvaDlXTEhsbzNZQW1STy9PL0xuNXV3QVBFdFBqdndOZlE2aGk0MTIzYnhDMmJkQlEvQWc3bDRIZnVNQ0ZtMEU5VGUwbDFDTWZOanVXbWZrbm1DQVRBNDhSak51NUdMVUo1cmtGWjRJb0krNGUxZDRObGhCTmxLOVIzdmRhNGVVS3B3NlB0RTByMUQ2ZXdDWGNYZFg4UFFkUXpaYnpTRVRBMW5kYUlmaWh0M2V3TFhmdE1rclZQNGd4bGJjdlEvNGpTYVRjZjhwbThiKzNaQm5sditnZlVQN2ZLb1ZROXU4d3NGZmhEV051L3NJZndCcHo5MVFITkUxcjNEMEo1RTE0dTUza0szcjFzZTdxeWgyc0pWWHFQV2I0Q054OTIzb0N4K25rRllNTFRPRWluSU1GM21GMmorS3J4RjN6ME9MSDFrTUNYajQxVnRsT0JpLzRRMmczbGRaR3VjVkdsMFZva0hjUFJlRCtkVmJSWEZGNi9CcXE4dWlpTGg3QkJwVlVmcWhjMTZoOVhXQk5PNnU5SVRWdklLVkMyTnAzRjF4Uko1WElFdkJ3UmNWL3dlOWVzdElmOEN4R2dBQUFBQkpSVTVFcmtKZ2dnPT0iIHByZXNlcnZlQXNwZWN0UmF0aW89Im5vbmUiIGhlaWdodD0iODQiIHdpZHRoPSIxOTIiIHk9IjAiIHg9IjAiLz4mI3hhOzwvc3ZnPg==;rotation=-180;" vertex="1" parent="1"> <mxGeometry x="955" y="-534" width="50" height="25" as="geometry" /> </mxCell> <mxCell id="3" value="" style="shape=image;verticalLabelPosition=bottom;labelBackgroundColor=default;verticalAlign=top;aspect=fixed;imageAspect=0;image=data:image/svg+xml,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;rotation=-210;" vertex="1" parent="1"> <mxGeometry x="1120" y="-540" width="50" height="25" as="geometry" /> </mxCell> <mxCell id="4" value="`t_2`" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=none;fillColor=none;" vertex="1" parent="1"> <mxGeometry x="1120" y="-509" width="50" height="30" as="geometry" /> </mxCell> <mxCell id="5" value="`t_1`" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=none;fillColor=none;" vertex="1" parent="1"> <mxGeometry x="955" y="-509" width="50" height="30" as="geometry" /> </mxCell> <mxCell id="6" value="" style="endArrow=classic;html=1;rounded=0;endSize=3;strokeColor=#3252FF;" edge="1" parent="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="967" y="-520" as="sourcePoint" /> <mxPoint x="1030" y="-520" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="7" value="" style="endArrow=classic;html=1;rounded=0;endSize=3;strokeColor=#3252FF;" edge="1" parent="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1134" y="-520" as="sourcePoint" /> <mxPoint x="1189" y="-551" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="8" value="" style="endArrow=classic;html=1;rounded=0;endSize=3;strokeColor=#3252FF;dashed=1;" edge="1" parent="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1134" y="-520" as="sourcePoint" /> <mxPoint x="1197" y="-520" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="9" value="" style="endArrow=classic;html=1;rounded=0;curved=1;endFill=1;endSize=2;strokeColor=#000000;" edge="1" parent="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1181" y="-520" as="sourcePoint" /> <mxPoint x="1178" y="-545" as="targetPoint" /> <Array as="points"> <mxPoint x="1182" y="-533" /> </Array> </mxGeometry> </mxCell> <mxCell id="10" value="&lt;span style=&quot;font-size: 10px;&quot;&gt;`\Deltayaw`&lt;/span&gt;" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=none;fillColor=none;" vertex="1" parent="1"> <mxGeometry x="1168" y="-549" width="70" height="30" as="geometry" /> </mxCell> <mxCell id="11" value="" style="endArrow=none;dashed=1;html=1;dashPattern=1 3;strokeWidth=2;rounded=0;" edge="1" parent="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1060" y="-519.92" as="sourcePoint" /> <mxPoint x="1095" y="-519.92" as="targetPoint" /> </mxGeometry> </mxCell> </root> </mxGraphModel> </diagram> </mxfile> " + viewBox="-0.5 -0.5 365 77" + content="<mxfile host="app.diagrams.net" modified="2024-04-18T12:50:45.453Z" agent="Mozilla/5.0 (X11; Linux x86_64) AppleWebKit/537.36 (KHTML, like Gecko) Chrome/122.0.0.0 Safari/537.36" version="24.2.5" etag="KrfeBttdqJpC7U2PhJCb" type="google" scale="1" border="0"> <diagram name="ページ1" id="3M-pu1oXXIi-LJN1ZMRq"> <mxGraphModel dx="722" dy="2026" grid="1" gridSize="10" guides="1" tooltips="1" connect="1" arrows="1" fold="0" page="1" pageScale="1" pageWidth="827" pageHeight="1169" math="1" shadow="0"> <root> <mxCell id="0" /> <mxCell id="1" parent="0" /> <mxCell id="2" value="" style="shape=image;verticalLabelPosition=bottom;labelBackgroundColor=default;verticalAlign=top;aspect=fixed;imageAspect=0;image=data:image/svg+xml,PHN2ZyB4bWxuczp4bGluaz0iaHR0cDovL3d3dy53My5vcmcvMTk5OS94bGluayIgeG1sbnM9Imh0dHA6Ly93d3cudzMub3JnLzIwMDAvc3ZnIiB4bWw6c3BhY2U9InByZXNlcnZlIiBzdHJva2UtbGluZWpvaW49InJvdW5kIiBzdHJva2Utd2lkdGg9IjI4LjIyMiIgdmVyc2lvbj0iMS4xIiB2aWV3Qm94PSIwIDAgMjAwIDEwMCIgaGVpZ2h0PSIxbW0iIHdpZHRoPSIybW0iPiYjeGE7IDxpbWFnZSB4bGluazpocmVmPSJkYXRhOmltYWdlL3BuZztiYXNlNjQsaVZCT1J3MEtHZ29BQUFBTlNVaEVVZ0FBQU1BQUFBQlVDQVlBQUFEVUt6aFNBQUFKckVsRVFWUjRuTzJkUFc3YlNoREhKNEQ3cUV1UndpcUM0SFZXL3dyekFnL1JEY3diV0Rjd0RRU3ZWazRRK2dSUmx6SjBFYVJsdW9kVWNwZDBTaTdnTnlNT3BlV1lsUGl4S3k3TitRRVRaaWw1ZHlYTmZ6OW1KUExzOGZFUmJQTFgyN2N6UEFSb2RKeXluVnR0UkJrTEQyaHJ0aFF0K2UvSGo5Um1BMmMyS2tHbm4rTWh0NWMyNmxRVXlBWk9za3UwS3pxQnZ2WWJEeXN5Rk1PcWF3T2RCSUNkQ2ZFUWdZN3d5dW1nQVpiRWNJWCtSek5FQkprWU5tMHFheVVBZFh6RkU4ai9QcUpGNkpNUmlpQnVXa0VqQVdBalV6eFFJNWRIbm5xUGxyQnRiSy9ibEhHQS9oYndmd08yS3IvYkNvRUg1aEQ5YlYyM2pkb0M0TXFYVUwzR0o2ZVBvY04wcENnbTZFY0ovM2Q3UkIrY1FMYlBES0ZjREhRdXhlY3Q2czRHdFFTQUZTN3hjRjN4OEIxYTFFUjFpdElHSGxoak1sNk5STUNiWXdNYW9HazJtT0h6RjhmcVBDb0FyQ2d1YVlUNGpyWXdWS29vSjRNSDNKRDljNGwySVo1eVRUTUdQaTg4Vk05QkFSeHcvbHVzT0tyWDFYN1J2TVJKeWVQMmY5QytvWDEydmYvakFYaEdtMkE4M29pSEtWSUVoMFJRS1FCZTlram5weGhzYUNQKzZoTE5TL1JHSHJjbi9rSDcxM2JjdmdvYWtMR3RGTElsa3ZtWmt3ZzJWY3VoVWdId2hsZXUrZW1GQkQ1SGRMamY3OUZlOTl3VlpZL1Z1UDBoU0dBY09VcWdLQUphRHFWbEcrTW5BdUROeFZLYzl0cjVOUzh4R0RySDdZOUJQbG9oZ2lXZVQyU3dwbXdHaU9IcHNpSDAwZmtiNUNVa2VaNGloZXo3SlJ1TDNXb0Z2cGJDbDdLd1R5LzY2a3NPdjc4QlpFdkpkdzMvZklNMnFYaXNkZHkrRGl3Q3F2dVRjWnA4T29iczlld29DSUQvU0RyVHJZOXIvaHA1aVVOY2d2RTZlV3BPd05FWHJvWUN4OWtEdzJSazVSQzd0VDd3b09JaWJsOFhYZzdkUW5GamZFbCtZN2ExRXdCM05oTDFmUGN4Mm5Na0wvRVY3U2ZhRzZqL0FkS0lkQVg3TDF6Undad2wxczlSRkx4VW1Cbld4T0VKQ29XdklGdlRwL0pCRjNIN0p2REdlQTdGMXhWeG43YVlNd0E5VWE2aHJYYklCazN5RWl6cUdSeFBwWmNoWjRtOGpRMXdaaEl5Y1d6NC8ydWZrb0VjL3Axd2NWcGliZlpMK1NpZlFNT05ySzI0ZlFzV2FGK004cms1QzVnQ2lNUWYzdm1XNUdxYWwrQVBLSUc5dzhxOEFCMmJPRUwrb1pVS2lVVmlCYmtuNkJFU2ZRS1p3eWRkSytzYXQyL1RIdFpKMzFZdy9ZYmFqdWsvV3dId05DRWRJYkxWQ1J2WXlrdndWSjBhOVU2Z0tJaW1HK3JuUnI0ZjJwcXJXYTF0M0w0bEVSUjloMmFCT2ZsTlBnUE14Ui9jZXphZGgrQW9MOEd6eElvdGIyOEd4Ylh4Y3hWRm5ybE5vSWVJV0p1NGZjdDIxbGdmN2VuTXozR09WaWtBS3czYm9JKzhoSndsdUI4VEtINmR3aXo3bUgvNGhmYktLSk96eDhETFFWK1d0MDNqOWgySTRha0E0SXhIdTBJbzBVV0NvZ014ZUpDWE1QWVRCVXJXc2w1OFQ0cWR5dHo4clgzb1Z4bE40dllkV0VHV2hOdlZUNzUvVnRMQXZhVUdPek9rdklUU2picHgrdzcxYjBxV1FRRUpZQ2FlbTNSdHpBWkR5a3NvZHFnVHQrOUlBa1VCYkdlQWFjbVRmR0FPQThoTEtOWlp3SUc0ZlVjU0tNNHcweklCK0VJa3l0N2xKUlQ3SEl2YmQyUWp5bHNCRkVaWkg1eHNDSGtKeFNrUlZNVHR1MVRLbTIzejFMbVZDMk01WUM3S1h1VWxGTGNjaXR2YmJtc29Bb2g3NklQU0x6R1V4TzF0NDUwQUJwQ1hVRTdEQ2tyaTlsNWVHOVF5Z1NoN2s1ZFFUa2RWM0I1RWhyNHJQZ3BnSnNwSkQzMVEvQ0FCRWJlMzNZQ1BBcGlLY3RKREh4US9TRURFN1cwM01BUUJLT05sSThwVDJ3MzRLQUR2OGhKS1A1VEY3VzIzNGFNQUZPVmtxQUNVVWFNQ1VFYU5Da0FaTlNvQVpkU29BSlJSb3dKUVJvMEtRQmsxS2dCbDFLZ0FsRkdqQWxCR2pRcEFHVFVxQUdYVXFBQ1VVYU1DVUVhTkNrQVpOU29BWmRUNEtBQzZqdjN1bHo4dUxvV2hEQU8reEx2SmcrMDJmQlRBR29vL2ZadjAwdzNGUTlhMksvUlZBUEphTUVrZkhWRjZKeERsdGUwR2ZCUkFDc1VMb3diOWRFUHhnRUNVVTlzTitDaUFSSlF2K2Y2eG14NzZvdlFFM3lCRjNoMG9zZDJPZHdMZ1MySFFUZkRNNjRQT1FTK1FPemJtb3Z6YlJUREVPd0V3S3lndWcwSlFBWXlOVUpSWExob1ppZ0JvR1RUVmV3U01BNzQxcmx6K3JGeTBSUUx3THU3T2R3d3M5QXV5dTRhRXZYUklPVFdSS0QvWXVETm9XVjZCQkxBR1ArUHVFUlN2RDMrRkx5RFdTeVUrYjloSnI4VHB5RkZ6NjF3QTNzWGQ2YVlZZkJOcVU1eExjSENKYk1VcmxxTDhZUEVHS1lFb2J3V1Fncjl4OXdpS3M4QUZpVUx2RmZ3ODRRSHZRcHlPTERZUmlISktBa2pFU1cvaTdqd0xoRkNjb1c3d1hLcDNpMzllOEoxQmI4VHBlMXVqZjFWZTRXd0FjZmNRc2xuSzdCOEpJempsWnAzZndCbGsxNmduTThzbUpGRDVRZmJCTDFHZThnaWJVTUdudlJUZkZ5NFdwOGtuUTR2TnpHWDk1RDk1R0hRRm5zYmQrWmFaQ3hBM1RFTkxYSW1BUHhEVDVNZ3hCRjZKTXUybGJ0aUFyN3RQa2JZMVpLSkk2WGpxbVovZmEyci9wWGhvWVRuc0hZcnlpdjZwRW9CWGNYZGVDczN3djlmRzZWd0VZWmZsRUkvc0FXU09Uc2NoT250Ynp0bDJyNW5EejBsdUxuMkFsejB4UEhYK0R6YnZESG9vcjdBVndCRGk3dGpIQlR1cktWUjY0ejdoK2R1NkcyTVdVZ0I3aDdkKzE1R0JRKy9IRlJ1OVg5OGhFOFBLNXJLSmwyTmxTOFU3K3F4dHRjTkVvcnpMSzV5Skoza2RkOGUraER4MXl6anhEWThtQzdPL3hybzlBRHVqT3puREJ2YUJneFQyOTdGYWR4a3RzYStQWmhucmV0RzJMcTV2QnZ1Y3psUVlQU1pIM1NvdTJLNTVyN2lDdlNBMkxmb1ZRQmJxbE5FZWdwdy9iRnBuamZZcTh3bzdBUXdsN3M0aTJFQnhPVVRRRy9vRkgvdUt4NTlvYjZEOFRhNEwzYU0yZ2N6SjEzMW54NXRTcDcvc0hEUERqcjFmSkpwOGR2aklzOE1LTWpFY2JJK1hJUkU4ZGNhY0R3NUdmbUlweW9XOGd2d3VVQVFEaUx2emNpaUY3TVhKa2V6dkZsWG02MTZxTXhtYXM3ZUZaOHNrTHh2N29keU9DU0tmSFc2TTJZRXM0UnRkVTMxenlKYlNWYk12L2QzQzVwby9wMDVlb1NDQUljWGR1YThKWkp1b3Brc2JjM1EvZWVURFYvaDlXTEhsbzNZQW1STy9PL0xuNXV3QVBFdFBqdndOZlE2aGk0MTIzYnhDMmJkQlEvQWc3bDRIZnVNQ0ZtMEU5VGUwbDFDTWZOanVXbWZrbm1DQVRBNDhSak51NUdMVUo1cmtGWjRJb0krNGUxZDRObGhCTmxLOVIzdmRhNGVVS3B3NlB0RTByMUQ2ZXdDWGNYZFg4UFFkUXpaYnpTRVRBMW5kYUlmaWh0M2V3TFhmdE1rclZQNGd4bGJjdlEvNGpTYVRjZjhwbThiKzNaQm5sditnZlVQN2ZLb1ZROXU4d3NGZmhEV051L3NJZndCcHo5MVFITkUxcjNEMEo1RTE0dTUza0szcjFzZTdxeWgyc0pWWHFQV2I0Q054OTIzb0N4K25rRllNTFRPRWluSU1GM21GMmorS3J4RjN6ME9MSDFrTUNYajQxVnRsT0JpLzRRMmczbGRaR3VjVkdsMFZva0hjUFJlRCtkVmJSWEZGNi9CcXE4dWlpTGg3QkJwVlVmcWhjMTZoOVhXQk5PNnU5SVRWdklLVkMyTnAzRjF4Uko1WElFdkJ3UmNWL3dlOWVzdElmOEN4R2dBQUFBQkpSVTVFcmtKZ2dnPT0iIHByZXNlcnZlQXNwZWN0UmF0aW89Im5vbmUiIGhlaWdodD0iODQiIHdpZHRoPSIxOTIiIHk9IjAiIHg9IjAiLz4mI3hhOzwvc3ZnPg==;rotation=-180;" vertex="1" parent="1"> <mxGeometry x="955" y="-534" width="50" height="25" as="geometry" /> </mxCell> <mxCell id="3" value="" style="shape=image;verticalLabelPosition=bottom;labelBackgroundColor=default;verticalAlign=top;aspect=fixed;imageAspect=0;image=data:image/svg+xml,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;rotation=-210;" vertex="1" parent="1"> <mxGeometry x="1120" y="-540" width="50" height="25" as="geometry" /> </mxCell> <mxCell id="4" value="`t_2`" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=none;fillColor=none;" vertex="1" parent="1"> <mxGeometry x="1120" y="-509" width="50" height="30" as="geometry" /> </mxCell> <mxCell id="5" value="`t_1`" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=none;fillColor=none;" vertex="1" parent="1"> <mxGeometry x="955" y="-509" width="50" height="30" as="geometry" /> </mxCell> <mxCell id="6" value="" style="endArrow=classic;html=1;rounded=0;endSize=3;strokeColor=#3252FF;" edge="1" parent="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="967" y="-520" as="sourcePoint" /> <mxPoint x="1030" y="-520" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="7" value="" style="endArrow=classic;html=1;rounded=0;endSize=3;strokeColor=#3252FF;" edge="1" parent="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1134" y="-520" as="sourcePoint" /> <mxPoint x="1189" y="-551" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="8" value="" style="endArrow=classic;html=1;rounded=0;endSize=3;strokeColor=#3252FF;dashed=1;" edge="1" parent="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1134" y="-520" as="sourcePoint" /> <mxPoint x="1197" y="-520" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="9" value="" style="endArrow=classic;html=1;rounded=0;curved=1;endFill=1;endSize=2;strokeColor=#000000;" edge="1" parent="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1181" y="-520" as="sourcePoint" /> <mxPoint x="1178" y="-545" as="targetPoint" /> <Array as="points"> <mxPoint x="1182" y="-533" /> </Array> </mxGeometry> </mxCell> <mxCell id="10" value="&lt;span style=&quot;font-size: 10px;&quot;&gt;`\Deltayaw`&lt;/span&gt;" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=none;fillColor=none;" vertex="1" parent="1"> <mxGeometry x="1168" y="-549" width="70" height="30" as="geometry" /> </mxCell> <mxCell id="11" value="&lt;span style=&quot;font-size: 10px;&quot;&gt;`\omega_{yaw} = (\Delta yaw) / (t2-t1)`&lt;/span&gt;" style="text;html=1;align=center;verticalAlign=middle;resizable=0;points=[];autosize=1;strokeColor=none;fillColor=none;" vertex="1" parent="1"> <mxGeometry x="1130" y="-511" width="190" height="30" as="geometry" /> </mxCell> <mxCell id="12" value="" style="endArrow=none;dashed=1;html=1;dashPattern=1 3;strokeWidth=2;rounded=0;" edge="1" parent="1"> <mxGeometry width="50" height="50" relative="1" as="geometry"> <mxPoint x="1060" y="-519.92" as="sourcePoint" /> <mxPoint x="1095" y="-519.92" as="targetPoint" /> </mxGeometry> </mxCell> </root> </mxGraphModel> </diagram> </mxfile> " >