Skip to content

Commit

Permalink
doc: add notification to duplicated lane matching algorithm
Browse files Browse the repository at this point in the history
Signed-off-by: Kotaro Yoshimoto <[email protected]>
  • Loading branch information
HansRobo committed Feb 19, 2024
1 parent 3871e20 commit 4e7f42f
Show file tree
Hide file tree
Showing 2 changed files with 3 additions and 0 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -473,6 +473,7 @@ auto EgoEntitySimulation::fillLaneletDataAndSnapZToLanelet(
traffic_simulator::helper::getUniqueValues(autoware->getRouteLanelets());
std::optional<traffic_simulator_msgs::msg::LaneletPose> lanelet_pose;

// the lanelet matching algorithm should be equivalent to the one used in EgoEntity::setMapPose
const auto get_matching_length = [&] {
return std::max(
vehicle_parameters.axles.front_axle.track_width,
Expand Down
2 changes: 2 additions & 0 deletions simulation/traffic_simulator/src/entity/ego_entity.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -275,6 +275,8 @@ auto EgoEntity::setMapPose(const geometry_msgs::msg::Pose & map_pose) -> void
{
const auto unique_route_lanelets = traffic_simulator::helper::getUniqueValues(getRouteLanelets());
std::optional<traffic_simulator_msgs::msg::LaneletPose> lanelet_pose;

// the lanelet matching algorithm should be equivalent to the one used in EgoEntitySimulation::fillLaneletDataAndSnapZToLanelet
const auto get_matching_length = [&] {
return std::max(
vehicle_parameters.axles.front_axle.track_width,
Expand Down

0 comments on commit 4e7f42f

Please sign in to comment.