Skip to content

Commit

Permalink
style(pre-commit): autofix
Browse files Browse the repository at this point in the history
  • Loading branch information
pre-commit-ci[bot] committed Mar 21, 2023
1 parent ae51565 commit 1a4f615
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 7 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -15,19 +15,19 @@
#ifndef SCENE_MODULE__INVALID_LANELET__UTIL_HPP_
#define SCENE_MODULE__INVALID_LANELET__UTIL_HPP_

#include <autoware_auto_planning_msgs/msg/path_with_lane_id.hpp>

#include <boost/geometry/geometries/linestring.hpp>
#include <boost/geometry/geometries/point_xy.hpp>

#include <lanelet2_core/primitives/Polygon.h>

#include <limits>
#include <memory>
#include <string>
#include <utility>
#include <vector>

#include <autoware_auto_planning_msgs/msg/path_with_lane_id.hpp>

#include <lanelet2_core/primitives/Polygon.h>

namespace behavior_velocity_planner
{

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ bool InvalidLaneletModule::modifyPathVelocity(PathWithLaneId * path, StopReason
path_invalid_lanelet_polygon_intersection.first_intersection_point.get();
distance_ego_first_intersection = motion_utils::calcSignedArcLength(
path->points, current_pose->pose.position, first_intersection_point);
distance_ego_first_intersection -= planner_data_->vehicle_info_.max_longitudinal_offset_m;
distance_ego_first_intersection -= planner_data_->vehicle_info_.max_longitudinal_offset_m;
}

debug_data_.path_polygon_intersection = path_invalid_lanelet_polygon_intersection;
Expand Down Expand Up @@ -190,8 +190,7 @@ bool InvalidLaneletModule::modifyPathVelocity(PathWithLaneId * path, StopReason
RCLCPP_INFO(logger_, "INSIDE_INVALID_LANELET");
}

const auto current_point =
planner_data_->current_odometry->pose.position;
const auto current_point = planner_data_->current_odometry->pose.position;
const size_t current_seg_idx = findEgoSegmentIndex(path->points);
// Insert stop point
planning_utils::insertStopPoint(current_point, current_seg_idx, *path);
Expand Down

0 comments on commit 1a4f615

Please sign in to comment.