Skip to content

Commit

Permalink
build(autoware_static_centerline_generator): fix missing includes
Browse files Browse the repository at this point in the history
Signed-off-by: Esteve Fernandez <[email protected]>
  • Loading branch information
esteve committed May 15, 2024
1 parent e1902a4 commit de05c29
Show file tree
Hide file tree
Showing 4 changed files with 9 additions and 0 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,9 @@

#include <nav_msgs/msg/odometry.hpp>

#include <memory>
#include <string>

namespace autoware::static_centerline_generator
{
std::vector<TrajectoryPoint> generate_centerline_with_bag(rclcpp::Node & node)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,8 @@
#include "tier4_autoware_utils/ros/parameter.hpp"
#include "utils.hpp"

#include <algorithm>

namespace autoware::static_centerline_generator
{
namespace
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,7 @@
#include <lanelet2_io/Io.h>
#include <lanelet2_projection/UTM.h>

#include <algorithm>
#include <chrono>
#include <filesystem>
#include <fstream>
Expand Down
3 changes: 3 additions & 0 deletions planning/autoware_static_centerline_generator/src/utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,9 @@

#include <lanelet2_core/LaneletMap.h>
#include <lanelet2_core/geometry/Lanelet.h>

#include <limits>

namespace autoware::static_centerline_generator
{
namespace
Expand Down

0 comments on commit de05c29

Please sign in to comment.