Skip to content

Commit e7ec3c5

Browse files
committed
fix spell
Signed-off-by: Mamoru Sobue <mamoru.sobue@tier4.jp>
1 parent 387f184 commit e7ec3c5

File tree

2 files changed

+6
-6
lines changed

2 files changed

+6
-6
lines changed

planning/mission_planner/src/lanelet2_plugins/default_planner.hpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -75,15 +75,15 @@ class DefaultPlanner : public mission_planner::PlannerPlugin
7575
/**
7676
* @brief check if the goal_footprint is within the combined lanelet of route_lanelets plus the
7777
* succeeding lanelets around the goal
78-
* @attetion this function will terminate when the accumulated search length from the initial
79-
* current_lanelet execeeds max_longitudinal_offset_m + search_margin, so under normal assumptions
78+
* @attention this function will terminate when the accumulated search length from the initial
79+
* current_lanelet exceeds max_longitudinal_offset_m + search_margin, so under normal assumptions
8080
* (i.e. the map is composed of finite elements of practically normal sized lanelets), it is
8181
* assured to terminate
8282
* @param current_lanelet the start lanelet to begin recursive query
8383
* @param combined_prev_lanelet initial entire route_lanelets plus the small consecutive lanelets
8484
* around the goal during the query
85-
* @param next_lane_length the accumulated total legth from the start lanelet of the search to the
86-
* lanelet of current goal query
85+
* @param next_lane_length the accumulated total length from the start lanelet of the search to
86+
* the lanelet of current goal query
8787
*/
8888
bool check_goal_footprint_inside_lanes(
8989
const lanelet::ConstLanelet & current_lanelet,

planning/mission_planner/src/lanelet2_plugins/utility_functions.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -84,7 +84,7 @@ lanelet::ConstLanelet combine_lanelets_with_shoulder(
8484
} else if (
8585
// if not exist, add left bound of lanelet to lefts
8686
// if the **left** of this lanelet does not match any of the **right** bounds of `lanelets`,
87-
// then its left bound consitutes the left boundary of the entire merged lanelet
87+
// then its left bound constitutes the left boundary of the entire merged lanelet
8888
std::count(right_bound_ids.begin(), right_bound_ids.end(), llt.leftBound().id()) < 1) {
8989
add_bound(llt.leftBound(), lefts);
9090
}
@@ -98,7 +98,7 @@ lanelet::ConstLanelet combine_lanelets_with_shoulder(
9898
} else if (
9999
// if not exist, add right bound of lanelet to rights
100100
// if the **right** of this lanelet does not match any of the **left** bounds of `lanelets`,
101-
// then its right bound consitutes the right bondary of the entire merged lanelet
101+
// then its right bound constitutes the right boundary of the entire merged lanelet
102102
std::count(left_bound_ids.begin(), left_bound_ids.end(), llt.rightBound().id()) < 1) {
103103
add_bound(llt.rightBound(), rights);
104104
}

0 commit comments

Comments
 (0)