diff --git a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/util.hpp b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/util.hpp index 791c35f3afca6..a7aec66f64363 100644 --- a/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/util.hpp +++ b/planning/behavior_path_goal_planner_module/include/behavior_path_goal_planner_module/util.hpp @@ -16,11 +16,10 @@ #define BEHAVIOR_PATH_GOAL_PLANNER_MODULE__UTIL_HPP_ #include "behavior_path_goal_planner_module/goal_searcher_base.hpp" -#include "behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp" -#include "behavior_path_planner_common/utils/utils.hpp" #include +#include "visualization_msgs/msg/detail/marker_array__struct.hpp" #include #include #include @@ -33,9 +32,7 @@ #include #include -namespace behavior_path_planner -{ -namespace goal_planner_utils +namespace behavior_path_planner::goal_planner_utils { using autoware_auto_perception_msgs::msg::PredictedObjects; using autoware_auto_perception_msgs::msg::PredictedPath; @@ -68,7 +65,6 @@ MarkerArray createGoalCandidatesMarkerArray( MarkerArray createNumObjectsToAvoidTextsMarkerArray( const GoalCandidates & goal_candidates, std::string && ns, const std_msgs::msg::ColorRGBA & color); -} // namespace goal_planner_utils -} // namespace behavior_path_planner +} // namespace behavior_path_planner::goal_planner_utils #endif // BEHAVIOR_PATH_GOAL_PLANNER_MODULE__UTIL_HPP_ diff --git a/planning/behavior_path_goal_planner_module/src/freespace_pull_over.cpp b/planning/behavior_path_goal_planner_module/src/freespace_pull_over.cpp index c9af9ee369bd5..6d3eb09bf4352 100644 --- a/planning/behavior_path_goal_planner_module/src/freespace_pull_over.cpp +++ b/planning/behavior_path_goal_planner_module/src/freespace_pull_over.cpp @@ -15,8 +15,10 @@ #include "behavior_path_goal_planner_module/freespace_pull_over.hpp" #include "behavior_path_goal_planner_module/util.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_utils.hpp" +#include "behavior_path_planner_common/utils/utils.hpp" #include #include diff --git a/planning/behavior_path_goal_planner_module/src/geometric_pull_over.cpp b/planning/behavior_path_goal_planner_module/src/geometric_pull_over.cpp index 31c1d3ef77b0e..b7d1c240d032a 100644 --- a/planning/behavior_path_goal_planner_module/src/geometric_pull_over.cpp +++ b/planning/behavior_path_goal_planner_module/src/geometric_pull_over.cpp @@ -15,6 +15,7 @@ #include "behavior_path_goal_planner_module/geometric_pull_over.hpp" #include "behavior_path_goal_planner_module/util.hpp" +#include "behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp" #include #include diff --git a/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp index 2ea6f1e100e91..3a8a17c3b0966 100644 --- a/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -16,6 +16,7 @@ #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" #include "behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp" diff --git a/planning/behavior_path_goal_planner_module/src/goal_searcher.cpp b/planning/behavior_path_goal_planner_module/src/goal_searcher.cpp index b087827a9c539..bf359be3de18b 100644 --- a/planning/behavior_path_goal_planner_module/src/goal_searcher.cpp +++ b/planning/behavior_path_goal_planner_module/src/goal_searcher.cpp @@ -17,6 +17,7 @@ #include "behavior_path_goal_planner_module/util.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/utils.hpp" #include "lanelet2_extension/regulatory_elements/no_parking_area.hpp" #include "lanelet2_extension/regulatory_elements/no_stopping_area.hpp" #include "lanelet2_extension/utility/utilities.hpp" diff --git a/planning/behavior_path_goal_planner_module/src/util.cpp b/planning/behavior_path_goal_planner_module/src/util.cpp index 23e9c53efae7b..1a1e66f85b403 100644 --- a/planning/behavior_path_goal_planner_module/src/util.cpp +++ b/planning/behavior_path_goal_planner_module/src/util.cpp @@ -14,9 +14,12 @@ #include "behavior_path_goal_planner_module/util.hpp" +#include "behavior_path_planner_common/utils/utils.hpp" + #include #include #include +#include #include @@ -30,17 +33,14 @@ #include #include +namespace behavior_path_planner::goal_planner_utils +{ + using tier4_autoware_utils::calcOffsetPose; using tier4_autoware_utils::createDefaultMarker; using tier4_autoware_utils::createMarkerColor; using tier4_autoware_utils::createMarkerScale; using tier4_autoware_utils::createPoint; - -namespace behavior_path_planner -{ -namespace goal_planner_utils -{ - lanelet::ConstLanelets getPullOverLanes( const RouteHandler & route_handler, const bool left_side, const double backward_distance, const double forward_distance) @@ -214,5 +214,4 @@ bool checkOriginalGoalIsInShoulder(const std::shared_ptr & route_h return false; } -} // namespace goal_planner_utils -} // namespace behavior_path_planner +} // namespace behavior_path_planner::goal_planner_utils diff --git a/planning/behavior_path_planner/package.xml b/planning/behavior_path_planner/package.xml index 0ca7badd0b3f4..2bc73325f96d5 100644 --- a/planning/behavior_path_planner/package.xml +++ b/planning/behavior_path_planner/package.xml @@ -56,7 +56,6 @@ pluginlib rclcpp rclcpp_components - route_handler sensor_msgs signal_processing tf2 diff --git a/planning/behavior_path_planner_common/CMakeLists.txt b/planning/behavior_path_planner_common/CMakeLists.txt index d1996bf72037f..dbbd7c7cedc67 100644 --- a/planning/behavior_path_planner_common/CMakeLists.txt +++ b/planning/behavior_path_planner_common/CMakeLists.txt @@ -4,7 +4,6 @@ project(behavior_path_planner_common) find_package(autoware_cmake REQUIRED) autoware_package() -find_package(OpenCV REQUIRED) find_package(magic_enum CONFIG REQUIRED) ament_auto_add_library(${PROJECT_NAME} SHARED @@ -31,10 +30,6 @@ target_include_directories(${PROJECT_NAME} SYSTEM PUBLIC ${EIGEN3_INCLUDE_DIR} ) -target_link_libraries(${PROJECT_NAME} - ${OpenCV_LIBRARIES} -) - if(BUILD_TESTING) ament_add_ros_isolated_gmock(test_${PROJECT_NAME}_utilities test/test_drivable_area_expansion.cpp diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/data_manager.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/data_manager.hpp index d52906ef4684f..31dc117fbce35 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/data_manager.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/data_manager.hpp @@ -21,7 +21,8 @@ #include "motion_utils/trajectory/trajectory.hpp" #include -#include +#include +#include #include #include @@ -38,12 +39,11 @@ #include #include -#include - #include #include #include #include +#include #include namespace behavior_path_planner @@ -100,7 +100,7 @@ struct DrivableAreaInfo { geometry_msgs::msg::Pose pose; tier4_autoware_utils::Polygon2d poly; - bool is_left; + bool is_left{true}; }; std::vector drivable_lanes{}; std::vector obstacles{}; // obstacles to extract from the drivable area @@ -136,7 +136,7 @@ struct BehaviorModuleOutput struct CandidateOutput { CandidateOutput() = default; - explicit CandidateOutput(const PathWithLaneId & path) : path_candidate{path} {} + explicit CandidateOutput(PathWithLaneId path) : path_candidate{std::move(path)} {} PathWithLaneId path_candidate{}; double lateral_shift{0.0}; double start_distance_to_path_change{std::numeric_limits::lowest()}; diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_manager_interface.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_manager_interface.hpp index 95976bf117096..43ecd17fa1844 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_manager_interface.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/scene_module_manager_interface.hpp @@ -19,10 +19,13 @@ #include "behavior_path_planner_common/interface/scene_module_interface.hpp" #include "tier4_autoware_utils/ros/parameter.hpp" -#include +#include +#include +#include #include +#include #include #include #include @@ -44,7 +47,11 @@ using SceneModuleObserver = std::weak_ptr; class SceneModuleManagerInterface { public: - explicit SceneModuleManagerInterface(const std::string & name) : name_{name} {} + SceneModuleManagerInterface(const SceneModuleManagerInterface &) = delete; + SceneModuleManagerInterface(SceneModuleManagerInterface &&) = delete; + SceneModuleManagerInterface & operator=(const SceneModuleManagerInterface &) = delete; + SceneModuleManagerInterface & operator=(SceneModuleManagerInterface &&) = delete; + explicit SceneModuleManagerInterface(std::string name) : name_{std::move(name)} {} virtual ~SceneModuleManagerInterface() = default; @@ -275,7 +282,7 @@ class SceneModuleManagerInterface for (const auto & rtc_type : rtc_types) { const auto snake_case_name = utils::convertToSnakeCase(name_); const auto rtc_interface_name = - rtc_type == "" ? snake_case_name : snake_case_name + "_" + rtc_type; + rtc_type.empty() ? snake_case_name : snake_case_name + "_" + rtc_type; rtc_interface_ptr_map_.emplace( rtc_type, std::make_shared(node, rtc_interface_name, config_.enable_rtc)); objects_of_interest_marker_interface_ptr_map_.emplace( @@ -298,7 +305,7 @@ class SceneModuleManagerInterface virtual std::unique_ptr createNewSceneModuleInstance() = 0; - rclcpp::Node * node_; + rclcpp::Node * node_ = nullptr; rclcpp::Publisher::SharedPtr pub_info_marker_; diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/steering_factor_interface.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/steering_factor_interface.hpp index fd3ce0097c2eb..fb0cb97a3db95 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/steering_factor_interface.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/interface/steering_factor_interface.hpp @@ -37,7 +37,7 @@ class SteeringFactorInterface void updateSteeringFactor( const std::array & poses, const std::array distances, const std::string & behavior, const uint16_t direction, const uint16_t status, - const std::string detail); + const std::string & detail); void clearSteeringFactors(); private: diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/marker_utils/colors.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/marker_utils/colors.hpp index 95dcff8602398..1c066ff744f46 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/marker_utils/colors.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/marker_utils/colors.hpp @@ -16,7 +16,7 @@ #include "tier4_autoware_utils/ros/marker_helper.hpp" -#include "std_msgs/msg/color_rgba.hpp" +#include "std_msgs/msg/detail/color_rgba__struct.hpp" #include diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/parameters.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/parameters.hpp index 5bdd0a2f3f88d..acda01dfc603c 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/parameters.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/parameters.hpp @@ -17,9 +17,6 @@ #include -#include -#include - struct ModuleConfigParameters { bool enable_module{false}; diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/turn_signal_decider.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/turn_signal_decider.hpp index 372041c7fb586..cd639b5e81092 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/turn_signal_decider.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/turn_signal_decider.hpp @@ -39,7 +39,7 @@ using geometry_msgs::msg::Point; using geometry_msgs::msg::Pose; using route_handler::RouteHandler; -const std::map signal_map = { +const std::map g_signal_map = { {"left", TurnIndicatorsCommand::ENABLE_LEFT}, {"right", TurnIndicatorsCommand::ENABLE_RIGHT}, {"straight", TurnIndicatorsCommand::DISABLE}, diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/drivable_area_expansion/footprints.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/drivable_area_expansion/footprints.hpp index 297092d0cdd68..2a4343e2c3f6a 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/drivable_area_expansion/footprints.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/drivable_area_expansion/footprints.hpp @@ -22,13 +22,6 @@ #include #include -#include - -#include -#include -#include -#include -#include namespace drivable_area_expansion { diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/drivable_area_expansion/path_projection.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/drivable_area_expansion/path_projection.hpp index 4c1469d46e03a..e60b35b95515f 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/drivable_area_expansion/path_projection.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/drivable_area_expansion/path_projection.hpp @@ -19,7 +19,7 @@ #include -#include +#include #include @@ -141,13 +141,11 @@ inline Segment2d linestring_to_point_projection( const auto lerp_ratio = (arc_length - prev_arc_length) / (curr_arc_length - prev_arc_length); const auto base_point = lerp_point(*std::prev(ls_iterator), *ls_iterator, lerp_ratio); - if (distance == 0.0) - return {base_point, base_point}; - else if (lerp_ratio >= 1.0) // base point is beyond the 2nd segment point -> calculate normal in - // the other direction + if (distance == 0.0) return {base_point, base_point}; + if (lerp_ratio >= 1.0) // base point is beyond the 2nd segment point -> calculate normal in + // the other direction return {base_point, normal_at_distance(base_point, *std::prev(ls_iterator), -distance)}; - else - return {base_point, normal_at_distance(base_point, *ls_iterator, distance)}; + return {base_point, normal_at_distance(base_point, *ls_iterator, distance)}; } /// @brief create a sub linestring between the given arc lengths diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/drivable_area_expansion/types.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/drivable_area_expansion/types.hpp index eae53b027655c..a7b91e5f7a8c9 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/drivable_area_expansion/types.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/drivable_area_expansion/types.hpp @@ -41,18 +41,18 @@ using tier4_autoware_utils::Point2d; using tier4_autoware_utils::Polygon2d; using tier4_autoware_utils::Segment2d; -typedef boost::geometry::index::rtree> SegmentRtree; +using SegmentRtree = boost::geometry::index::rtree>; struct PointDistance { Point2d point; - double distance; + double distance{0.0}; }; struct Projection { Point2d projected_point; - double distance; - double arc_length; + double distance{0.0}; + double arc_length{0.0}; }; enum Side { LEFT, RIGHT }; diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp index c24aa021cf57c..5b1e9b4b4c419 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp @@ -21,14 +21,6 @@ #include #include -#include - -#ifdef ROS_DISTRO_GALACTIC -#include -#else -#include -#endif - #include namespace behavior_path_planner @@ -74,8 +66,8 @@ struct OccupancyGridMapParam VehicleShape vehicle_shape; // costmap configs - int theta_size; // discretized angle table size [-] - int obstacle_threshold; // obstacle threshold on grid [-] + int theta_size{0}; // discretized angle table size [-] + int obstacle_threshold{0}; // obstacle threshold on grid [-] }; struct PlannerWaypoint @@ -93,7 +85,12 @@ struct PlannerWaypoints class OccupancyGridBasedCollisionDetector { public: - OccupancyGridBasedCollisionDetector() {} + OccupancyGridBasedCollisionDetector() = default; + OccupancyGridBasedCollisionDetector(const OccupancyGridBasedCollisionDetector &) = default; + OccupancyGridBasedCollisionDetector(OccupancyGridBasedCollisionDetector &&) = delete; + OccupancyGridBasedCollisionDetector & operator=(const OccupancyGridBasedCollisionDetector &) = + default; + OccupancyGridBasedCollisionDetector & operator=(OccupancyGridBasedCollisionDetector &&) = delete; void setParam(const OccupancyGridMapParam & param) { param_ = param; }; OccupancyGridMapParam getParam() const { return param_; }; void setMap(const nav_msgs::msg::OccupancyGrid & costmap); @@ -106,7 +103,7 @@ class OccupancyGridBasedCollisionDetector const bool check_out_of_range) const; const PlannerWaypoints & getWaypoints() const { return waypoints_; } bool detectCollision(const IndexXYT & base_index, const bool check_out_of_range) const; - virtual ~OccupancyGridBasedCollisionDetector() {} + virtual ~OccupancyGridBasedCollisionDetector() = default; protected: void computeCollisionIndexes(int theta_index, std::vector & indexes); diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure/common_module_data.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure/common_module_data.hpp index c270a1500431c..74f6b843803df 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure/common_module_data.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure/common_module_data.hpp @@ -17,8 +17,6 @@ #include "behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" -#include - #include #include diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp index 4d1f1fdb959c0..26c0f247eb558 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp @@ -18,15 +18,10 @@ #include "behavior_path_planner_common/data_manager.hpp" #include "behavior_path_planner_common/parameters.hpp" -#include -#include - #include #include #include -#include -#include -#include +#include #include @@ -40,7 +35,6 @@ using autoware_auto_planning_msgs::msg::PathPointWithLaneId; using autoware_auto_planning_msgs::msg::PathWithLaneId; using geometry_msgs::msg::Point; using geometry_msgs::msg::Pose; -using geometry_msgs::msg::PoseArray; struct ParallelParkingParameters { diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure/utils.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure/utils.hpp index 1d4245bfec0e4..bdcc9dcb2cc6a 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure/utils.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/parking_departure/utils.hpp @@ -19,8 +19,6 @@ #include "behavior_path_planner_common/utils/parking_departure/common_module_data.hpp" #include "behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" -#include - #include #include #include diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp index f66f425f1b7fa..e33c2596ab04d 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp @@ -23,8 +23,6 @@ #include #include -#include -#include #include #include diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp index fcb4f3f4dc207..13009d5114439 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp @@ -26,14 +26,6 @@ #include #include -#include - -#ifdef ROS_DISTRO_GALACTIC -#include -#else -#include -#endif - #include namespace behavior_path_planner::utils::path_safety_checker diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_shifter/path_shifter.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_shifter/path_shifter.hpp index 099adc21d2ad7..165a11ebb54b4 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_shifter/path_shifter.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_shifter/path_shifter.hpp @@ -15,11 +15,13 @@ #ifndef BEHAVIOR_PATH_PLANNER_COMMON__UTILS__PATH_SHIFTER__PATH_SHIFTER_HPP_ #define BEHAVIOR_PATH_PLANNER_COMMON__UTILS__PATH_SHIFTER__PATH_SHIFTER_HPP_ -#include +#include +#include #include #include +#include #include #include #include diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/utils.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/utils.hpp index e2c9fd1e332a2..01b2880f4362a 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/utils.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/utils.hpp @@ -16,7 +16,6 @@ #define BEHAVIOR_PATH_PLANNER_COMMON__UTILS__UTILS_HPP_ #include "behavior_path_planner_common/data_manager.hpp" -#include "behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" #include "motion_utils/trajectory/trajectory.hpp" #include @@ -34,18 +33,10 @@ #include #include -#include - -#ifdef ROS_DISTRO_GALACTIC -#include -#else -#include -#endif #include #include #include -#include #include namespace behavior_path_planner::utils @@ -55,34 +46,21 @@ using autoware_auto_perception_msgs::msg::PredictedObject; using autoware_auto_perception_msgs::msg::PredictedObjects; using autoware_auto_perception_msgs::msg::PredictedPath; -using autoware_auto_perception_msgs::msg::Shape; -using autoware_auto_planning_msgs::msg::Path; using autoware_auto_planning_msgs::msg::PathPointWithLaneId; using autoware_auto_planning_msgs::msg::PathWithLaneId; using geometry_msgs::msg::Point; using geometry_msgs::msg::Pose; -using geometry_msgs::msg::PoseArray; -using geometry_msgs::msg::Twist; using geometry_msgs::msg::Vector3; -using path_safety_checker::ExtendedPredictedObject; -using path_safety_checker::ObjectTypesToCheck; -using path_safety_checker::PoseWithVelocityAndPolygonStamped; -using path_safety_checker::PoseWithVelocityStamped; -using path_safety_checker::PredictedPathWithPolygon; -using path_safety_checker::SafetyCheckParams; -using path_safety_checker::TargetObjectsOnLane; using route_handler::RouteHandler; using tier4_autoware_utils::LinearRing2d; -using tier4_autoware_utils::LineString2d; using tier4_autoware_utils::Polygon2d; -using vehicle_info_util::VehicleInfo; struct PolygonPoint { geometry_msgs::msg::Point point; - size_t bound_seg_idx; - double lon_dist_to_segment; - double lat_dist_to_bound; + size_t bound_seg_idx{0}; + double lon_dist_to_segment{0.0}; + double lat_dist_to_bound{0.0}; bool is_after(const PolygonPoint & other_point) const { diff --git a/planning/behavior_path_planner_common/package.xml b/planning/behavior_path_planner_common/package.xml index 4bb6901625a19..83e9c39e24dd6 100644 --- a/planning/behavior_path_planner_common/package.xml +++ b/planning/behavior_path_planner_common/package.xml @@ -50,8 +50,6 @@ geometry_msgs interpolation lanelet2_extension - libboost-dev - libopencv-dev magic_enum motion_utils object_recognition_utils @@ -59,11 +57,7 @@ rclcpp route_handler rtc_interface - sensor_msgs tf2 - tf2_eigen - tf2_geometry_msgs - tf2_ros tier4_autoware_utils tier4_planning_msgs vehicle_info_util diff --git a/planning/behavior_path_planner_common/src/interface/steering_factor_interface.cpp b/planning/behavior_path_planner_common/src/interface/steering_factor_interface.cpp index 93ae7e8289902..cbced86865a99 100644 --- a/planning/behavior_path_planner_common/src/interface/steering_factor_interface.cpp +++ b/planning/behavior_path_planner_common/src/interface/steering_factor_interface.cpp @@ -34,12 +34,12 @@ void SteeringFactorInterface::publishSteeringFactor(const rclcpp::Time & stamp) void SteeringFactorInterface::updateSteeringFactor( const std::array & pose, const std::array distance, const std::string & behavior, const uint16_t direction, const uint16_t status, - const std::string detail) + const std::string & detail) { std::lock_guard lock(mutex_); SteeringFactor factor; factor.pose = pose; - std::array converted_distance; + std::array converted_distance{0.0, 0.0}; for (int i = 0; i < 2; ++i) converted_distance[i] = static_cast(distance[i]); factor.distance = converted_distance; factor.behavior = behavior; diff --git a/planning/behavior_path_planner_common/src/marker_utils/utils.cpp b/planning/behavior_path_planner_common/src/marker_utils/utils.cpp index 4dc422a81d22c..ec182ae5b909a 100644 --- a/planning/behavior_path_planner_common/src/marker_utils/utils.cpp +++ b/planning/behavior_path_planner_common/src/marker_utils/utils.cpp @@ -30,9 +30,7 @@ namespace marker_utils { -using behavior_path_planner::ShiftLine; using behavior_path_planner::utils::calcPathArcLengthArray; -using behavior_path_planner::utils::path_safety_checker::CollisionCheckDebug; using std_msgs::msg::ColorRGBA; using tier4_autoware_utils::calcOffsetPose; using tier4_autoware_utils::createDefaultMarker; @@ -101,7 +99,7 @@ MarkerArray createShiftLineMarkerArray( { ShiftLineArray shift_lines_local = shift_lines; if (shift_lines.empty()) { - shift_lines_local.push_back(ShiftLine()); + shift_lines_local.emplace_back(); } MarkerArray msg; @@ -289,8 +287,8 @@ MarkerArray createFurthestLineStringMarkerArray(const lanelet::ConstLineStrings3 const bool isFrontNear = tier4_autoware_utils::calcDistance2d(marker_back, front) < tier4_autoware_utils::calcDistance2d(marker_back, front_inverted); const auto & left_ls = (isFrontNear) ? idx->basicLineString() : idx->invert().basicLineString(); - for (auto ls = left_ls.cbegin(); ls != left_ls.cend(); ++ls) { - marker.points.push_back(createPoint(ls->x(), ls->y(), ls->z())); + for (const auto & left_l : left_ls) { + marker.points.push_back(createPoint(left_l.x(), left_l.y(), left_l.z())); } } diff --git a/planning/behavior_path_planner_common/src/turn_signal_decider.cpp b/planning/behavior_path_planner_common/src/turn_signal_decider.cpp index 933330dafae7e..44358dfa84e4e 100644 --- a/planning/behavior_path_planner_common/src/turn_signal_decider.cpp +++ b/planning/behavior_path_planner_common/src/turn_signal_decider.cpp @@ -266,7 +266,7 @@ std::optional TurnSignalDecider::getIntersectionTurnSignalInfo( turn_signal_info.required_start_point = lane_front_pose; turn_signal_info.required_end_point = get_required_end_point(combined_lane.centerline3d()); turn_signal_info.desired_end_point = lane_back_pose; - turn_signal_info.turn_signal.command = signal_map.at(lane_attribute); + turn_signal_info.turn_signal.command = g_signal_map.at(lane_attribute); signal_queue.push(turn_signal_info); } } diff --git a/planning/behavior_path_planner_common/src/utils/drivable_area_expansion/drivable_area_expansion.cpp b/planning/behavior_path_planner_common/src/utils/drivable_area_expansion/drivable_area_expansion.cpp index 4fe9a3cd6e10f..866d114815a86 100644 --- a/planning/behavior_path_planner_common/src/utils/drivable_area_expansion/drivable_area_expansion.cpp +++ b/planning/behavior_path_planner_common/src/utils/drivable_area_expansion/drivable_area_expansion.cpp @@ -20,14 +20,13 @@ #include "behavior_path_planner_common/utils/drivable_area_expansion/path_projection.hpp" #include "behavior_path_planner_common/utils/drivable_area_expansion/types.hpp" -#include #include #include #include #include #include -#include +#include #include diff --git a/planning/behavior_path_planner_common/src/utils/drivable_area_expansion/footprints.cpp b/planning/behavior_path_planner_common/src/utils/drivable_area_expansion/footprints.cpp index 6b323be6c6328..787af681bf69b 100644 --- a/planning/behavior_path_planner_common/src/utils/drivable_area_expansion/footprints.cpp +++ b/planning/behavior_path_planner_common/src/utils/drivable_area_expansion/footprints.cpp @@ -19,10 +19,7 @@ #include #include -#include - -#include -#include +#include #include diff --git a/planning/behavior_path_planner_common/src/utils/drivable_area_expansion/map_utils.cpp b/planning/behavior_path_planner_common/src/utils/drivable_area_expansion/map_utils.cpp index 2eb55599b83f9..8420ee96b0ba6 100644 --- a/planning/behavior_path_planner_common/src/utils/drivable_area_expansion/map_utils.cpp +++ b/planning/behavior_path_planner_common/src/utils/drivable_area_expansion/map_utils.cpp @@ -14,7 +14,7 @@ #include "behavior_path_planner_common/utils/drivable_area_expansion/map_utils.hpp" -#include +#include #include #include diff --git a/planning/behavior_path_planner_common/src/utils/parking_departure/geometric_parallel_parking.cpp b/planning/behavior_path_planner_common/src/utils/parking_departure/geometric_parallel_parking.cpp index 7ba4f114328a7..a1a079e679e72 100644 --- a/planning/behavior_path_planner_common/src/utils/parking_departure/geometric_parallel_parking.cpp +++ b/planning/behavior_path_planner_common/src/utils/parking_departure/geometric_parallel_parking.cpp @@ -23,38 +23,22 @@ #include #include -#include - -#ifdef ROS_DISTRO_GALACTIC -#include -#include -#else -#include - -#include +#include #include -#endif - -#include +#include #include #include using autoware_auto_planning_msgs::msg::PathWithLaneId; using geometry_msgs::msg::Point; using geometry_msgs::msg::Pose; -using geometry_msgs::msg::PoseArray; -using geometry_msgs::msg::Transform; -using geometry_msgs::msg::TransformStamped; using lanelet::utils::getArcCoordinates; using tier4_autoware_utils::calcDistance2d; using tier4_autoware_utils::calcOffsetPose; -using tier4_autoware_utils::deg2rad; using tier4_autoware_utils::inverseTransformPoint; -using tier4_autoware_utils::inverseTransformPose; using tier4_autoware_utils::normalizeRadian; -using tier4_autoware_utils::toMsg; using tier4_autoware_utils::transformPose; namespace behavior_path_planner @@ -518,15 +502,11 @@ std::vector GeometricParallelParking::planOneTrial( // set terminal velocity and acceleration(temporary implementation) if (is_forward) { - pairs_terminal_velocity_and_accel_.push_back( - std::make_pair(parameters_.forward_parking_velocity, 0.0)); - pairs_terminal_velocity_and_accel_.push_back( - std::make_pair(parameters_.forward_parking_velocity, 0.0)); + pairs_terminal_velocity_and_accel_.emplace_back(parameters_.forward_parking_velocity, 0.0); + pairs_terminal_velocity_and_accel_.emplace_back(parameters_.forward_parking_velocity, 0.0); } else { - pairs_terminal_velocity_and_accel_.push_back( - std::make_pair(parameters_.backward_parking_velocity, 0.0)); - pairs_terminal_velocity_and_accel_.push_back( - std::make_pair(parameters_.backward_parking_velocity, 0.0)); + pairs_terminal_velocity_and_accel_.emplace_back(parameters_.backward_parking_velocity, 0.0); + pairs_terminal_velocity_and_accel_.emplace_back(parameters_.backward_parking_velocity, 0.0); } // set pull_over start and end pose diff --git a/planning/behavior_path_planner_common/src/utils/parking_departure/utils.cpp b/planning/behavior_path_planner_common/src/utils/parking_departure/utils.cpp index 58fd392988ad9..a7b1df45c8150 100644 --- a/planning/behavior_path_planner_common/src/utils/parking_departure/utils.cpp +++ b/planning/behavior_path_planner_common/src/utils/parking_departure/utils.cpp @@ -17,6 +17,7 @@ #include "behavior_path_planner_common/utils/utils.hpp" #include +#include namespace behavior_path_planner::utils::parking_departure { diff --git a/planning/behavior_path_planner_common/src/utils/path_utils.cpp b/planning/behavior_path_planner_common/src/utils/path_utils.cpp index 57a5743a5963b..2eceb0ffb81c8 100644 --- a/planning/behavior_path_planner_common/src/utils/path_utils.cpp +++ b/planning/behavior_path_planner_common/src/utils/path_utils.cpp @@ -186,16 +186,15 @@ size_t getIdxByArclength( } } return path.points.size() - 1; - } else { - for (size_t i = target_idx; i > 0; --i) { - const auto next_i = i - 1; - sum_length -= calcDistance2d(path.points.at(i), path.points.at(next_i)); - if (sum_length < signed_arc) { - return next_i; - } + } + for (size_t i = target_idx; i > 0; --i) { + const auto next_i = i - 1; + sum_length -= calcDistance2d(path.points.at(i), path.points.at(next_i)); + if (sum_length < signed_arc) { + return next_i; } - return 0; } + return 0; } // TODO(murooka) This function should be replaced with motion_utils::cropPoints diff --git a/planning/behavior_path_planner_common/src/utils/utils.cpp b/planning/behavior_path_planner_common/src/utils/utils.cpp index 7c3a5883989fb..e6f9ce21cebf7 100644 --- a/planning/behavior_path_planner_common/src/utils/utils.cpp +++ b/planning/behavior_path_planner_common/src/utils/utils.cpp @@ -14,7 +14,6 @@ #include "behavior_path_planner_common/utils/utils.hpp" -#include "behavior_path_planner_common/utils/path_shifter/path_shifter.hpp" #include "motion_utils/trajectory/path_with_lane_id.hpp" #include "object_recognition_utils/predicted_path_utils.hpp" @@ -22,6 +21,7 @@ #include #include #include +#include #include #include @@ -74,7 +74,7 @@ namespace behavior_path_planner::utils using autoware_auto_perception_msgs::msg::ObjectClassification; using autoware_auto_perception_msgs::msg::Shape; using geometry_msgs::msg::PoseWithCovarianceStamped; -using tf2::fromMsg; +using tier4_autoware_utils::LineString2d; using tier4_autoware_utils::Point2d; std::optional getPolygonByPoint(