Skip to content

Commit

Permalink
chore(utils): move utils directory (autowarefoundation#2911)
Browse files Browse the repository at this point in the history
Signed-off-by: satoshi-ota <[email protected]>
  • Loading branch information
satoshi-ota authored Feb 20, 2023
1 parent ab0e97a commit ce82f3d
Show file tree
Hide file tree
Showing 27 changed files with 36 additions and 37 deletions.
6 changes: 3 additions & 3 deletions planning/behavior_path_planner/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -35,10 +35,10 @@ ament_auto_add_library(behavior_path_planner_node SHARED
src/scene_module/pull_out/util.cpp
src/scene_module/pull_out/shift_pull_out.cpp
src/scene_module/pull_out/geometric_pull_out.cpp
src/scene_module/utils/geometric_parallel_parking.cpp
src/scene_module/utils/occupancy_grid_based_collision_detector.cpp
src/scene_module/utils/path_shifter.cpp
src/scene_module/scene_module_visitor.cpp
src/util/geometric_parallel_parking/geometric_parallel_parking.cpp
src/util/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.cpp
src/util/path_shifter/path_shifter.cpp
src/util/drivable_area_expansion/drivable_area_expansion.cpp
src/util/drivable_area_expansion/map_utils.cpp
src/util/drivable_area_expansion/footprints.cpp
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@
#ifndef BEHAVIOR_PATH_PLANNER__DEBUG_UTILITIES_HPP_
#define BEHAVIOR_PATH_PLANNER__DEBUG_UTILITIES_HPP_

#include "behavior_path_planner/scene_module/utils/path_shifter.hpp"
#include "behavior_path_planner/util/path_shifter/path_shifter.hpp"
#include "tier4_autoware_utils/tier4_autoware_utils.hpp"

#include <tier4_autoware_utils/ros/marker_helper.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,9 @@
#ifndef BEHAVIOR_PATH_PLANNER__PATH_UTILITIES_HPP_
#define BEHAVIOR_PATH_PLANNER__PATH_UTILITIES_HPP_

#include "behavior_path_planner/util/path_shifter/path_shifter.hpp"

#include <behavior_path_planner/parameters.hpp>
#include <behavior_path_planner/scene_module/utils/path_shifter.hpp>

#include <autoware_auto_planning_msgs/msg/path.hpp>
#include <autoware_auto_planning_msgs/msg/path_with_lane_id.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@
#include "behavior_path_planner/scene_module/avoidance/avoidance_module_data.hpp"
#include "behavior_path_planner/scene_module/scene_module_interface.hpp"
#include "behavior_path_planner/scene_module/scene_module_visitor.hpp"
#include "behavior_path_planner/scene_module/utils/path_shifter.hpp"

#include <rclcpp/rclcpp.hpp>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
#ifndef BEHAVIOR_PATH_PLANNER__SCENE_MODULE__AVOIDANCE__AVOIDANCE_MODULE_DATA_HPP_
#define BEHAVIOR_PATH_PLANNER__SCENE_MODULE__AVOIDANCE__AVOIDANCE_MODULE_DATA_HPP_

#include "behavior_path_planner/scene_module/utils/path_shifter.hpp"
#include "behavior_path_planner/util/path_shifter/path_shifter.hpp"

#include <rclcpp/rclcpp.hpp>
#include <tier4_autoware_utils/tier4_autoware_utils.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,6 @@

#include "behavior_path_planner/debug_utilities.hpp"
#include "behavior_path_planner/scene_module/avoidance/avoidance_module_data.hpp"
#include "behavior_path_planner/scene_module/utils/path_shifter.hpp"

#include <tier4_autoware_utils/ros/marker_helper.hpp>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
#include "behavior_path_planner/scene_module/lane_change/lane_change_path.hpp"
#include "behavior_path_planner/scene_module/scene_module_interface.hpp"
#include "behavior_path_planner/turn_signal_decider.hpp"
#include "behavior_path_planner/util/path_shifter/path_shifter.hpp"

#include <rclcpp/rclcpp.hpp>

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

#include "behavior_path_planner/scene_module/lane_change/lane_change_module_data.hpp"
#include "behavior_path_planner/scene_module/utils/path_shifter.hpp"
#include "behavior_path_planner/turn_signal_decider.hpp"

#include <autoware_auto_planning_msgs/msg/path_with_lane_id.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@

#include "behavior_path_planner/scene_module/pull_out/pull_out_path.hpp"
#include "behavior_path_planner/scene_module/pull_out/pull_out_planner_base.hpp"
#include "behavior_path_planner/scene_module/utils/geometric_parallel_parking.hpp"
#include "behavior_path_planner/util/geometric_parallel_parking/geometric_parallel_parking.hpp"

#include <autoware_auto_planning_msgs/msg/path_with_lane_id.hpp>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,8 +20,8 @@
#include "behavior_path_planner/scene_module/pull_out/pull_out_path.hpp"
#include "behavior_path_planner/scene_module/pull_out/shift_pull_out.hpp"
#include "behavior_path_planner/scene_module/scene_module_interface.hpp"
#include "behavior_path_planner/scene_module/utils/geometric_parallel_parking.hpp"
#include "behavior_path_planner/scene_module/utils/path_shifter.hpp"
#include "behavior_path_planner/util/geometric_parallel_parking/geometric_parallel_parking.hpp"
#include "behavior_path_planner/util/path_shifter/path_shifter.hpp"

#include <lane_departure_checker/lane_departure_checker.hpp>
#include <lanelet2_extension/utility/message_conversion.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
#ifndef BEHAVIOR_PATH_PLANNER__SCENE_MODULE__PULL_OUT__PULL_OUT_PATH_HPP_
#define BEHAVIOR_PATH_PLANNER__SCENE_MODULE__PULL_OUT__PULL_OUT_PATH_HPP_

#include "behavior_path_planner/scene_module/utils/path_shifter.hpp"
#include "behavior_path_planner/util/path_shifter/path_shifter.hpp"

#include <autoware_auto_planning_msgs/msg/path_with_lane_id.hpp>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,8 +16,8 @@
#define BEHAVIOR_PATH_PLANNER__SCENE_MODULE__PULL_OVER__GEOMETRIC_PULL_OVER_HPP_

#include "behavior_path_planner/scene_module/pull_over/pull_over_planner_base.hpp"
#include "behavior_path_planner/scene_module/utils/geometric_parallel_parking.hpp"
#include "behavior_path_planner/scene_module/utils/occupancy_grid_based_collision_detector.hpp"
#include "behavior_path_planner/util/geometric_parallel_parking/geometric_parallel_parking.hpp"
#include "behavior_path_planner/util/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp"

#include <lane_departure_checker/lane_departure_checker.hpp>

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

#include "behavior_path_planner/scene_module/pull_over/goal_searcher_base.hpp"
#include "behavior_path_planner/scene_module/utils/occupancy_grid_based_collision_detector.hpp"
#include "behavior_path_planner/util/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp"

#include "autoware_auto_planning_msgs/msg/path_point_with_lane_id.hpp"

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,8 +20,8 @@
#include "behavior_path_planner/scene_module/pull_over/pull_over_parameters.hpp"
#include "behavior_path_planner/scene_module/pull_over/shift_pull_over.hpp"
#include "behavior_path_planner/scene_module/scene_module_interface.hpp"
#include "behavior_path_planner/scene_module/utils/geometric_parallel_parking.hpp"
#include "behavior_path_planner/scene_module/utils/occupancy_grid_based_collision_detector.hpp"
#include "behavior_path_planner/util/geometric_parallel_parking/geometric_parallel_parking.hpp"
#include "behavior_path_planner/util/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp"

#include <lane_departure_checker/lane_departure_checker.hpp>

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

#include "behavior_path_planner/scene_module/pull_over/pull_over_planner_base.hpp"
#include "behavior_path_planner/scene_module/utils/occupancy_grid_based_collision_detector.hpp"
#include "behavior_path_planner/util/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp"

#include <lane_departure_checker/lane_departure_checker.hpp>

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

#include "behavior_path_planner/scene_module/scene_module_interface.hpp"
#include "behavior_path_planner/scene_module/utils/path_shifter.hpp"
#include "behavior_path_planner/util/path_shifter/path_shifter.hpp"

#include <rclcpp/rclcpp.hpp>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef BEHAVIOR_PATH_PLANNER__SCENE_MODULE__UTILS__GEOMETRIC_PARALLEL_PARKING_HPP_
#define BEHAVIOR_PATH_PLANNER__SCENE_MODULE__UTILS__GEOMETRIC_PARALLEL_PARKING_HPP_
#ifndef BEHAVIOR_PATH_PLANNER__UTIL__GEOMETRIC_PARALLEL_PARKING__GEOMETRIC_PARALLEL_PARKING_HPP_
#define BEHAVIOR_PATH_PLANNER__UTIL__GEOMETRIC_PARALLEL_PARKING__GEOMETRIC_PARALLEL_PARKING_HPP_

#include "behavior_path_planner/data_manager.hpp"
#include "behavior_path_planner/parameters.hpp"
Expand Down Expand Up @@ -129,4 +129,4 @@ class GeometricParallelParking
};
} // namespace behavior_path_planner

#endif // BEHAVIOR_PATH_PLANNER__SCENE_MODULE__UTILS__GEOMETRIC_PARALLEL_PARKING_HPP_
#endif // BEHAVIOR_PATH_PLANNER__UTIL__GEOMETRIC_PARALLEL_PARKING__GEOMETRIC_PARALLEL_PARKING_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef BEHAVIOR_PATH_PLANNER__SCENE_MODULE__UTILS__OCCUPANCY_GRID_BASED_COLLISION_DETECTOR_HPP_
#define BEHAVIOR_PATH_PLANNER__SCENE_MODULE__UTILS__OCCUPANCY_GRID_BASED_COLLISION_DETECTOR_HPP_
#ifndef BEHAVIOR_PATH_PLANNER__UTIL__OCCUPANCY_GRID_BASED_COLLISION_DETECTOR__OCCUPANCY_GRID_BASED_COLLISION_DETECTOR_HPP_
#define BEHAVIOR_PATH_PLANNER__UTIL__OCCUPANCY_GRID_BASED_COLLISION_DETECTOR__OCCUPANCY_GRID_BASED_COLLISION_DETECTOR_HPP_

#include <tier4_autoware_utils/geometry/geometry.hpp>

Expand Down Expand Up @@ -149,4 +149,4 @@ class OccupancyGridBasedCollisionDetector

} // namespace behavior_path_planner

#endif // BEHAVIOR_PATH_PLANNER__SCENE_MODULE__UTILS__OCCUPANCY_GRID_BASED_COLLISION_DETECTOR_HPP_
#endif // BEHAVIOR_PATH_PLANNER__UTIL__OCCUPANCY_GRID_BASED_COLLISION_DETECTOR__OCCUPANCY_GRID_BASED_COLLISION_DETECTOR_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef BEHAVIOR_PATH_PLANNER__SCENE_MODULE__UTILS__PATH_SHIFTER_HPP_
#define BEHAVIOR_PATH_PLANNER__SCENE_MODULE__UTILS__PATH_SHIFTER_HPP_
#ifndef BEHAVIOR_PATH_PLANNER__UTIL__PATH_SHIFTER__PATH_SHIFTER_HPP_
#define BEHAVIOR_PATH_PLANNER__UTIL__PATH_SHIFTER__PATH_SHIFTER_HPP_

#include "behavior_path_planner/parameters.hpp"

Expand Down Expand Up @@ -226,4 +226,4 @@ class PathShifter

} // namespace behavior_path_planner

#endif // BEHAVIOR_PATH_PLANNER__SCENE_MODULE__UTILS__PATH_SHIFTER_HPP_
#endif // BEHAVIOR_PATH_PLANNER__UTIL__PATH_SHIFTER__PATH_SHIFTER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "behavior_path_planner/scene_module/utils/path_shifter.hpp"
#include "behavior_path_planner/util/path_shifter/path_shifter.hpp"

#include <behavior_path_planner/scene_module/lane_change/debug.hpp>
#include <tier4_autoware_utils/ros/marker_helper.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
#include "behavior_path_planner/path_utilities.hpp"
#include "behavior_path_planner/scene_module/lane_change/lane_change_module_data.hpp"
#include "behavior_path_planner/scene_module/lane_change/lane_change_path.hpp"
#include "behavior_path_planner/scene_module/utils/path_shifter.hpp"
#include "behavior_path_planner/util/path_shifter/path_shifter.hpp"
#include "behavior_path_planner/utilities.hpp"

#include <lanelet2_extension/utility/message_conversion.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,8 @@
#include "behavior_path_planner/scene_module/pull_out/util.hpp"

#include "behavior_path_planner/path_utilities.hpp"
#include "behavior_path_planner/scene_module/utils/path_shifter.hpp"
#include "behavior_path_planner/util/create_vehicle_footprint.hpp"
#include "behavior_path_planner/util/path_shifter/path_shifter.hpp"

#include <lanelet2_extension/utility/utilities.hpp>
#include <rclcpp/rclcpp.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,8 +16,8 @@

#include "behavior_path_planner/path_utilities.hpp"
#include "behavior_path_planner/scene_module/pull_over/util.hpp"
#include "behavior_path_planner/scene_module/utils/path_shifter.hpp"
#include "behavior_path_planner/util/create_vehicle_footprint.hpp"
#include "behavior_path_planner/util/path_shifter/path_shifter.hpp"
#include "behavior_path_planner/utilities.hpp"

#include <lanelet2_extension/utility/message_conversion.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
#include "behavior_path_planner/scene_module/pull_over/util.hpp"

#include "behavior_path_planner/path_utilities.hpp"
#include "behavior_path_planner/scene_module/utils/path_shifter.hpp"
#include "behavior_path_planner/util/path_shifter/path_shifter.hpp"

#include <lanelet2_extension/utility/query.hpp>
#include <lanelet2_extension/utility/utilities.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "behavior_path_planner/scene_module/utils/geometric_parallel_parking.hpp"
#include "behavior_path_planner/util/geometric_parallel_parking/geometric_parallel_parking.hpp"

#include "behavior_path_planner/path_utilities.hpp"
#include "behavior_path_planner/utilities.hpp"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "behavior_path_planner/scene_module/utils/occupancy_grid_based_collision_detector.hpp"
#include "behavior_path_planner/util/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp"

#include <tier4_autoware_utils/geometry/geometry.hpp>
#include <tier4_autoware_utils/tier4_autoware_utils.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "behavior_path_planner/scene_module/utils/path_shifter.hpp"
#include "behavior_path_planner/util/path_shifter/path_shifter.hpp"

#include "behavior_path_planner/path_utilities.hpp"
#include "behavior_path_planner/utilities.hpp"
Expand Down

0 comments on commit ce82f3d

Please sign in to comment.