diff --git a/localization/yabloc/yabloc_image_processing/README.md b/localization/yabloc/yabloc_image_processing/README.md
index bc31c579d39a1..eb9ae658c39a7 100644
--- a/localization/yabloc/yabloc_image_processing/README.md
+++ b/localization/yabloc/yabloc_image_processing/README.md
@@ -53,15 +53,15 @@ This node extract road surface region by [graph-based-segmentation](https://docs
### Parameters
-| Name | Type | Description |
-| -------------------------------- | ------ | ------------------------------------------------------------------ |
-| `target_height_ratio` | double | height on the image to retrieve the candidate road surface |
-| `target_candidate_box_width` | int | size of the square area to search for candidate road surfaces |
-| `pickup_addtional_graph_segment` | bool | if this is true, additional regions of similar color are retrieved |
-| `similarity_score_threshold` | double | threshold for picking up additional areas |
-| `sigma` | double | parameters for cv::ximgproc::segmentation |
-| `k` | double | parameters for cv::ximgproc::segmentation |
-| `min_size` | double | parameters for cv::ximgproc::segmentation |
+| Name | Type | Description |
+| --------------------------------- | ------ | ------------------------------------------------------------------ |
+| `target_height_ratio` | double | height on the image to retrieve the candidate road surface |
+| `target_candidate_box_width` | int | size of the square area to search for candidate road surfaces |
+| `pickup_additional_graph_segment` | bool | if this is true, additional regions of similar color are retrieved |
+| `similarity_score_threshold` | double | threshold for picking up additional areas |
+| `sigma` | double | parameters for cv::ximgproc::segmentation |
+| `k` | double | parameters for cv::ximgproc::segmentation |
+| `min_size` | double | parameters for cv::ximgproc::segmentation |
## segment_filter
@@ -91,7 +91,7 @@ This is a node that integrates the results of graph_segment and lsd to extract r
| Name | Type | Description |
| -------------------------------------- | ------ | ------------------------------------------------------------------- |
-| `min_segment_length` | double | min lenght threshold (if it is negative, it is unlimited) |
+| `min_segment_length` | double | min length threshold (if it is negative, it is unlimited) |
| `max_segment_distance` | double | max distance threshold (if it is negative, it is unlimited) |
| `max_lateral_distance` | double | max lateral distance threshold (if it is negative, it is unlimited) |
| `publish_image_with_segment_for_debug` | bool | toggle whether to publish the filtered line segment for debug |
@@ -178,7 +178,7 @@ This node overlays lanelet2 on the camera image based on the estimated self-posi
| Name | Type | Description |
| ------------------------------- | --------------------------------- | ------------------------------------------------------ |
-| `output/lanelet2_overlay_image` | `sensor_msgs::msg::Image` | lanelet2 overlayed image |
+| `output/lanelet2_overlay_image` | `sensor_msgs::msg::Image` | lanelet2 overlaid image |
| `output/projected_marker` | `visualization_msgs::msg::Marker` | 3d projected line segments including non-road markings |
## line_segments_overlay
@@ -193,7 +193,7 @@ This node visualize classified line segments on the camera image
| Name | Type | Description |
| --------------------------- | ------------------------------- | ------------------------ |
-| `input/line_segments_cloud` | `sensor_msgs::msg::PointCloud2` | classied line segments |
+| `input/line_segments_cloud` | `sensor_msgs::msg::PointCloud2` | classified line segments |
| `input/image_raw` | `sensor_msgs::msg::Image` | undistorted camera image |
#### Output
diff --git a/localization/yabloc/yabloc_image_processing/launch/image_processing.launch.xml b/localization/yabloc/yabloc_image_processing/launch/image_processing.launch.xml
index 0d3850bf74590..b7caea8236a7f 100644
--- a/localization/yabloc/yabloc_image_processing/launch/image_processing.launch.xml
+++ b/localization/yabloc/yabloc_image_processing/launch/image_processing.launch.xml
@@ -33,7 +33,7 @@
-
+
diff --git a/localization/yabloc/yabloc_image_processing/launch/overlay.launch.xml b/localization/yabloc/yabloc_image_processing/launch/overlay.launch.xml
index 70c3e8f553446..715ed31405a87 100644
--- a/localization/yabloc/yabloc_image_processing/launch/overlay.launch.xml
+++ b/localization/yabloc/yabloc_image_processing/launch/overlay.launch.xml
@@ -1,5 +1,5 @@
-
+
@@ -13,7 +13,7 @@
-
+
diff --git a/localization/yabloc/yabloc_image_processing/launch/yabloc_image_processing.launch.xml b/localization/yabloc/yabloc_image_processing/launch/yabloc_image_processing.launch.xml
index 8fab2731fe24e..847b4ac03295c 100644
--- a/localization/yabloc/yabloc_image_processing/launch/yabloc_image_processing.launch.xml
+++ b/localization/yabloc/yabloc_image_processing/launch/yabloc_image_processing.launch.xml
@@ -15,7 +15,7 @@
-
+
diff --git a/localization/yabloc/yabloc_image_processing/src/lanelet2_overlay/lanelet2_overlay_core.cpp b/localization/yabloc/yabloc_image_processing/src/lanelet2_overlay/lanelet2_overlay_core.cpp
index 9d27636f16e9d..367ff51567147 100644
--- a/localization/yabloc/yabloc_image_processing/src/lanelet2_overlay/lanelet2_overlay_core.cpp
+++ b/localization/yabloc/yabloc_image_processing/src/lanelet2_overlay/lanelet2_overlay_core.cpp
@@ -116,20 +116,20 @@ void Lanelet2Overlay::draw_overlay(
{
if (ll2_cloud_.empty()) return;
- cv::Mat overlayed_image = cv::Mat::zeros(image.size(), CV_8UC3);
+ cv::Mat overlaid_image = cv::Mat::zeros(image.size(), CV_8UC3);
using common::extract_near_line_segments;
if (pose) {
draw_overlay_line_segments(
- overlayed_image, *pose,
+ overlaid_image, *pose,
extract_near_line_segments(ll2_cloud_, common::pose_to_se3(*pose), 60));
draw_overlay_line_segments(
- overlayed_image, *pose,
+ overlaid_image, *pose,
extract_near_line_segments(sign_board_, common::pose_to_se3(*pose), 60));
}
cv::Mat show_image;
- cv::addWeighted(image, 0.8, overlayed_image, 0.8, 1, show_image);
+ cv::addWeighted(image, 0.8, overlaid_image, 0.8, 1, show_image);
common::publish_image(*pub_image_, show_image, stamp);
}
diff --git a/localization/yabloc/yabloc_particle_filter/launch/yabloc_particle_filter.launch.xml b/localization/yabloc/yabloc_particle_filter/launch/yabloc_particle_filter.launch.xml
index fcbf64441ffd4..47a478b2adbdf 100644
--- a/localization/yabloc/yabloc_particle_filter/launch/yabloc_particle_filter.launch.xml
+++ b/localization/yabloc/yabloc_particle_filter/launch/yabloc_particle_filter.launch.xml
@@ -2,7 +2,7 @@
-
+
@@ -31,7 +31,7 @@
-
+
@@ -50,7 +50,7 @@
-
+
diff --git a/localization/yabloc/yabloc_particle_filter/src/common/particle_visualize_node.cpp b/localization/yabloc/yabloc_particle_filter/src/common/particle_visualize_node.cpp
index efe84cec7fb6c..90cd62883e339 100644
--- a/localization/yabloc/yabloc_particle_filter/src/common/particle_visualize_node.cpp
+++ b/localization/yabloc/yabloc_particle_filter/src/common/particle_visualize_node.cpp
@@ -20,7 +20,7 @@
#include
#include
-namespace yabloc::modularized_particle_fitler
+namespace yabloc::modularized_particle_filter
{
class ParticleVisualize : public rclcpp::Node
{
@@ -103,13 +103,13 @@ class ParticleVisualize : public rclcpp::Node
pub_marker_array->publish(marker_array);
}
};
-} // namespace yabloc::modularized_particle_fitler
+} // namespace yabloc::modularized_particle_filter
int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);
- rclcpp::spin(std::make_shared());
+ rclcpp::spin(std::make_shared());
rclcpp::shutdown();
return 0;
}