Skip to content

Commit

Permalink
fix(autoware_static_centerline_optimizer): fix clang-tidy issues
Browse files Browse the repository at this point in the history
Signed-off-by: Esteve Fernandez <[email protected]>
  • Loading branch information
esteve committed Apr 12, 2024
1 parent c22cdbf commit 066eac5
Show file tree
Hide file tree
Showing 4 changed files with 6 additions and 3 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,8 @@

namespace autoware::static_centerline_optimizer
{
using ::tier4_autoware_utils::Point2d;

namespace
{
Path convert_to_path(const PathWithLaneId & path_with_lane_id)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,7 @@ namespace autoware::static_centerline_optimizer
using autoware_static_centerline_optimizer::srv::LoadMap;
using autoware_static_centerline_optimizer::srv::PlanPath;
using autoware_static_centerline_optimizer::srv::PlanRoute;
using ::route_handler::RouteHandler;

class StaticCenterlineOptimizerNode : public rclcpp::Node
{
Expand Down
2 changes: 0 additions & 2 deletions planning/static_centerline_optimizer/src/type_alias.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,10 +36,8 @@ using autoware_auto_planning_msgs::msg::PathWithLaneId;
using autoware_auto_planning_msgs::msg::Trajectory;
using autoware_auto_planning_msgs::msg::TrajectoryPoint;
using autoware_planning_msgs::msg::LaneletRoute;
using route_handler::RouteHandler;
using tier4_autoware_utils::LinearRing2d;
using tier4_autoware_utils::LineString2d;
using tier4_autoware_utils::Point2d;
using visualization_msgs::msg::MarkerArray;
} // namespace autoware::static_centerline_optimizer

Expand Down
4 changes: 3 additions & 1 deletion planning/static_centerline_optimizer/src/utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,12 +26,14 @@

namespace autoware::static_centerline_optimizer::utils
{
using ::route_handler::RouteHandler;

geometry_msgs::msg::Pose get_center_pose(
const RouteHandler & route_handler, const size_t lanelet_id);

PathWithLaneId get_path_with_lane_id(
const RouteHandler & route_handler, const lanelet::ConstLanelets & lanelets,
const geometry_msgs::msg::Pose & start_pose, const double nearest_ego_dist_threshold,
const geometry_msgs::msg::Pose & start_pose, const double ego_nearest_dist_threshold,
const double nearest_ego_yaw_threshold);

void update_centerline(
Expand Down

0 comments on commit 066eac5

Please sign in to comment.