Skip to content

Commit

Permalink
refactor(behavior_path_planner): remove create_vehicle_footprint.hpp (a…
Browse files Browse the repository at this point in the history
…utowarefoundation#6049)

Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>
  • Loading branch information
satoshi-ota authored and karishma1911 committed May 26, 2024
1 parent 333e978 commit 7eba929
Show file tree
Hide file tree
Showing 7 changed files with 6 additions and 59 deletions.
1 change: 0 additions & 1 deletion planning/behavior_path_avoidance_module/src/utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,6 @@

#include "behavior_path_avoidance_module/data_structs.hpp"
#include "behavior_path_avoidance_module/utils.hpp"
#include "behavior_path_planner_common/utils/create_vehicle_footprint.hpp"
#include "behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp"
#include "behavior_path_planner_common/utils/path_utils.hpp"
#include "behavior_path_planner_common/utils/traffic_light_utils.hpp"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,6 @@

#include "behavior_path_goal_planner_module/goal_planner_parameters.hpp"
#include "behavior_path_planner_common/data_manager.hpp"
#include "behavior_path_planner_common/utils/create_vehicle_footprint.hpp"

#include <autoware_auto_planning_msgs/msg/path_with_lane_id.hpp>
#include <geometry_msgs/msg/pose_stamped.hpp>
Expand Down Expand Up @@ -114,7 +113,7 @@ class PullOverPlannerBase
PullOverPlannerBase(rclcpp::Node & node, const GoalPlannerParameters & parameters)
{
vehicle_info_ = vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo();
vehicle_footprint_ = createVehicleFootprint(vehicle_info_);
vehicle_footprint_ = vehicle_info_.createFootprint();
parameters_ = parameters;
}
virtual ~PullOverPlannerBase() = default;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,6 @@
#include "behavior_path_goal_planner_module/goal_planner_module.hpp"

#include "behavior_path_goal_planner_module/util.hpp"
#include "behavior_path_planner_common/utils/create_vehicle_footprint.hpp"
#include "behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp"
#include "behavior_path_planner_common/utils/parking_departure/utils.hpp"
#include "behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp"
Expand Down Expand Up @@ -94,7 +93,7 @@ GoalPlannerModule::GoalPlannerModule(
// set selected goal searcher
// currently there is only one goal_searcher_type
const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo();
vehicle_footprint_ = createVehicleFootprint(vehicle_info);
vehicle_footprint_ = vehicle_info.createFootprint();
goal_searcher_ =
std::make_shared<GoalSearcher>(*parameters, vehicle_footprint_, occupancy_grid_map_);

Expand Down

This file was deleted.

Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,6 @@
#define BEHAVIOR_PATH_START_PLANNER_MODULE__PULL_OUT_PLANNER_BASE_HPP_

#include "behavior_path_planner_common/data_manager.hpp"
#include "behavior_path_planner_common/utils/create_vehicle_footprint.hpp"
#include "behavior_path_start_planner_module/pull_out_path.hpp"
#include "behavior_path_start_planner_module/start_planner_parameters.hpp"

Expand Down Expand Up @@ -45,7 +44,7 @@ class PullOutPlannerBase
explicit PullOutPlannerBase(rclcpp::Node & node, const StartPlannerParameters & parameters)
{
vehicle_info_ = vehicle_info_util::VehicleInfoUtil(node).getVehicleInfo();
vehicle_footprint_ = createVehicleFootprint(vehicle_info_);
vehicle_footprint_ = vehicle_info_.createFootprint();
parameters_ = parameters;
}
virtual ~PullOutPlannerBase() = default;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,6 @@

#include "behavior_path_start_planner_module/start_planner_module.hpp"

#include "behavior_path_planner_common/utils/create_vehicle_footprint.hpp"
#include "behavior_path_planner_common/utils/parking_departure/utils.hpp"
#include "behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp"
#include "behavior_path_planner_common/utils/path_utils.hpp"
Expand Down Expand Up @@ -623,7 +622,7 @@ bool StartPlannerModule::findPullOutPath(
const auto & dynamic_objects = planner_data_->dynamic_object;
const auto pull_out_lanes = start_planner_utils::getPullOutLanes(
planner_data_, planner_data_->parameters.backward_path_length + parameters_->max_back_distance);
const auto & vehicle_footprint = createVehicleFootprint(vehicle_info_);
const auto & vehicle_footprint = vehicle_info_.createFootprint();
// extract stop objects in pull out lane for collision check
const auto stop_objects = utils::path_safety_checker::filterObjectsByVelocity(
*dynamic_objects, parameters_->th_moving_object_velocity);
Expand Down Expand Up @@ -902,7 +901,7 @@ std::vector<Pose> StartPlannerModule::searchPullOutStartPoseCandidates(
{
std::vector<Pose> pull_out_start_pose_candidates{};
const auto start_pose = planner_data_->route_handler->getOriginalStartPose();
const auto local_vehicle_footprint = createVehicleFootprint(vehicle_info_);
const auto local_vehicle_footprint = vehicle_info_.createFootprint();
const auto pull_out_lanes = start_planner_utils::getPullOutLanes(
planner_data_, planner_data_->parameters.backward_path_length + parameters_->max_back_distance);
const double backward_path_length =
Expand Down Expand Up @@ -1356,7 +1355,7 @@ void StartPlannerModule::setDebugData() const

// visualize collision_check_end_pose and footprint
{
const auto local_footprint = createVehicleFootprint(vehicle_info_);
const auto local_footprint = vehicle_info_.createFootprint();
const auto collision_check_end_pose = motion_utils::calcLongitudinalOffsetPose(
getFullPath().points, status_.pull_out_path.end_pose.position,
parameters_->collision_check_distance_from_end);
Expand Down
1 change: 0 additions & 1 deletion planning/behavior_path_start_planner_module/src/util.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,6 @@

#include "behavior_path_start_planner_module/util.hpp"

#include "behavior_path_planner_common/utils/create_vehicle_footprint.hpp"
#include "behavior_path_planner_common/utils/path_shifter/path_shifter.hpp"
#include "behavior_path_planner_common/utils/path_utils.hpp"
#include "behavior_path_planner_common/utils/utils.hpp"
Expand Down

0 comments on commit 7eba929

Please sign in to comment.