Skip to content

Commit

Permalink
Ros2 v0.8 fix typo of "preceding" (autowarefoundation#323)
Browse files Browse the repository at this point in the history
* Fix typo of getPrecedingLaneletSequences

* Fix comment
  • Loading branch information
isamu-takagi authored Feb 10, 2021
1 parent 9f77981 commit 7cce819
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 6 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -217,15 +217,15 @@ std::vector<lanelet::ConstLanelets> getSucceedingLaneletSequences(
const double length);

/**
* [getPreceedingLaneletSequences retrieves a sequence of lanelets before the given lanelet.
* [getPrecedingLaneletSequences retrieves a sequence of lanelets before the given lanelet.
* The total length of retrieved lanelet sequence at least given length. Returned lanelet sequence
* does not include input lanelet.]
* @param graph [input lanelet routing graph]
* @param lanelet [input lanelet]
* @param length [minimum length of retrieved lanelet sequence]
* @return [lanelet sequence that leads to given lanelet]
*/
std::vector<lanelet::ConstLanelets> getPreceedingLaneletSequences(
std::vector<lanelet::ConstLanelets> getPrecedingLaneletSequences(
const routing::RoutingGraphPtr & graph, const lanelet::ConstLanelet & lanelet,
const double length);

Expand Down
8 changes: 4 additions & 4 deletions map/lanelet2_extension/lib/query.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -721,7 +721,7 @@ std::vector<std::deque<lanelet::ConstLanelet>> getSucceedingLaneletSequencesRecu
return succeeding_lanelet_sequences;
}

std::vector<std::deque<lanelet::ConstLanelet>> getPreceedingLaneletSequencesRecursive(
std::vector<std::deque<lanelet::ConstLanelet>> getPrecedingLaneletSequencesRecursive(
const routing::RoutingGraphPtr & graph, const lanelet::ConstLanelet & lanelet,
const double length)
{
Expand All @@ -739,7 +739,7 @@ std::vector<std::deque<lanelet::ConstLanelet>> getPreceedingLaneletSequencesRecu
for (const auto & prev_lanelet : prev_lanelets) {
// get lanelet sequence after prev_lanelet
auto tmp_lanelet_sequences =
getPreceedingLaneletSequencesRecursive(graph, prev_lanelet, length - lanelet_length);
getPrecedingLaneletSequencesRecursive(graph, prev_lanelet, length - lanelet_length);
for (auto & tmp_lanelet_sequence : tmp_lanelet_sequences) {
tmp_lanelet_sequence.push_back(lanelet);
preceding_lanelet_sequences.push_back(tmp_lanelet_sequence);
Expand All @@ -764,7 +764,7 @@ std::vector<lanelet::ConstLanelets> query::getSucceedingLaneletSequences(
return lanelet_sequences_vec;
}

std::vector<lanelet::ConstLanelets> query::getPreceedingLaneletSequences(
std::vector<lanelet::ConstLanelets> query::getPrecedingLaneletSequences(
const routing::RoutingGraphPtr & graph, const lanelet::ConstLanelet & lanelet,
const double length)
{
Expand All @@ -773,7 +773,7 @@ std::vector<lanelet::ConstLanelets> query::getPreceedingLaneletSequences(
for (const auto & prev_lanelet : prev_lanelets) {
// convert deque into vector
const auto lanelet_sequences_deq =
getPreceedingLaneletSequencesRecursive(graph, prev_lanelet, length);
getPrecedingLaneletSequencesRecursive(graph, prev_lanelet, length);
for (const auto & lanelet_sequence : lanelet_sequences_deq) {
lanelet_sequences_vec.emplace_back(lanelet_sequence.begin(), lanelet_sequence.end());
}
Expand Down

0 comments on commit 7cce819

Please sign in to comment.