Skip to content

Commit

Permalink
Update EgoEntity::setMapPose to not call getRouteLanelets
Browse files Browse the repository at this point in the history
Signed-off-by: yamacir-kit <[email protected]>
  • Loading branch information
yamacir-kit committed Jan 27, 2025
1 parent b1fc84b commit a663fc4
Showing 1 changed file with 7 additions and 1 deletion.
8 changes: 7 additions & 1 deletion simulation/traffic_simulator/src/entity/ego_entity.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -283,7 +283,13 @@ auto EgoEntity::setMapPose(const geometry_msgs::msg::Pose & map_pose) -> void
entity_status.lanelet_pose_valid = false;
// prefer current lanelet on Autoware side
status_->set(
entity_status, helper::getUniqueValues(getRouteLanelets()),
entity_status, helper::getUniqueValues([this]() {
auto ids = lanelet::Ids();
for (const auto & point : getPathWithLaneId().points) {
ids += point.lane_ids;
}
return ids;
}()),
getDefaultMatchingDistanceForLaneletPoseCalculation());
}
} // namespace entity
Expand Down

0 comments on commit a663fc4

Please sign in to comment.