Skip to content

Commit

Permalink
refactor(behavior_path_planner_common): remove unused headers (autowa…
Browse files Browse the repository at this point in the history
…refoundation#5924)

Signed-off-by: Zulfaqar Azmi <[email protected]>
  • Loading branch information
zulfaqar-azmi-t4 authored and karishma1911 committed Jun 3, 2024
1 parent d9d7f8d commit 9855c95
Show file tree
Hide file tree
Showing 36 changed files with 84 additions and 170 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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 <lane_departure_checker/lane_departure_checker.hpp>

#include "visualization_msgs/msg/detail/marker_array__struct.hpp"
#include <autoware_auto_perception_msgs/msg/predicted_objects.hpp>
#include <autoware_auto_perception_msgs/msg/predicted_path.hpp>
#include <autoware_auto_planning_msgs/msg/path_with_lane_id.hpp>
Expand All @@ -33,9 +32,7 @@
#include <string>
#include <vector>

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;
Expand Down Expand Up @@ -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_
Original file line number Diff line number Diff line change
Expand Up @@ -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 <memory>
#include <vector>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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 <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 @@ -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"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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"
Expand Down
15 changes: 7 additions & 8 deletions planning/behavior_path_goal_planner_module/src/util.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,9 +14,12 @@

#include "behavior_path_goal_planner_module/util.hpp"

#include "behavior_path_planner_common/utils/utils.hpp"

#include <lanelet2_extension/utility/query.hpp>
#include <lanelet2_extension/utility/utilities.hpp>
#include <rclcpp/rclcpp.hpp>
#include <tier4_autoware_utils/ros/marker_helper.hpp>

#include <boost/geometry/algorithms/dispatch/distance.hpp>

Expand All @@ -30,17 +33,14 @@
#include <string>
#include <vector>

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)
Expand Down Expand Up @@ -214,5 +214,4 @@ bool checkOriginalGoalIsInShoulder(const std::shared_ptr<RouteHandler> & route_h
return false;
}

} // namespace goal_planner_utils
} // namespace behavior_path_planner
} // namespace behavior_path_planner::goal_planner_utils
1 change: 0 additions & 1 deletion planning/behavior_path_planner/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,6 @@
<depend>pluginlib</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>route_handler</depend>
<depend>sensor_msgs</depend>
<depend>signal_processing</depend>
<depend>tf2</depend>
Expand Down
5 changes: 0 additions & 5 deletions planning/behavior_path_planner_common/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,8 @@
#include "motion_utils/trajectory/trajectory.hpp"

#include <lanelet2_extension/regulatory_elements/Forward.hpp>
#include <rclcpp/rclcpp.hpp>
#include <rclcpp/rclcpp/clock.hpp>
#include <rclcpp/rclcpp/time.hpp>
#include <route_handler/route_handler.hpp>

#include <autoware_adapi_v1_msgs/msg/operation_mode_state.hpp>
Expand All @@ -38,12 +39,11 @@
#include <nav_msgs/msg/odometry.hpp>
#include <tier4_planning_msgs/msg/lateral_offset.hpp>

#include <lanelet2_core/primitives/Lanelet.h>

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

namespace behavior_path_planner
Expand Down Expand Up @@ -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<DrivableLanes> drivable_lanes{};
std::vector<Obstacle> obstacles{}; // obstacles to extract from the drivable area
Expand Down Expand Up @@ -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<double>::lowest()};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,10 +19,13 @@
#include "behavior_path_planner_common/interface/scene_module_interface.hpp"
#include "tier4_autoware_utils/ros/parameter.hpp"

#include <rclcpp/rclcpp.hpp>
#include <rclcpp/node.hpp>
#include <rclcpp/parameter.hpp>
#include <rclcpp/publisher.hpp>

#include <unique_identifier_msgs/msg/uuid.hpp>

#include <cstddef>
#include <limits>
#include <memory>
#include <string>
Expand All @@ -44,7 +47,11 @@ using SceneModuleObserver = std::weak_ptr<SceneModuleInterface>;
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;

Expand Down Expand Up @@ -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<RTCInterface>(node, rtc_interface_name, config_.enable_rtc));
objects_of_interest_marker_interface_ptr_map_.emplace(
Expand All @@ -298,7 +305,7 @@ class SceneModuleManagerInterface

virtual std::unique_ptr<SceneModuleInterface> createNewSceneModuleInstance() = 0;

rclcpp::Node * node_;
rclcpp::Node * node_ = nullptr;

rclcpp::Publisher<MarkerArray>::SharedPtr pub_info_marker_;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ class SteeringFactorInterface
void updateSteeringFactor(
const std::array<Pose, 2> & poses, const std::array<double, 2> distances,
const std::string & behavior, const uint16_t direction, const uint16_t status,
const std::string detail);
const std::string & detail);
void clearSteeringFactors();

private:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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 <vector>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,9 +17,6 @@

#include <vehicle_info_util/vehicle_info_util.hpp>

#include <utility>
#include <vector>

struct ModuleConfigParameters
{
bool enable_module{false};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ using geometry_msgs::msg::Point;
using geometry_msgs::msg::Pose;
using route_handler::RouteHandler;

const std::map<std::string, uint8_t> signal_map = {
const std::map<std::string, uint8_t> g_signal_map = {
{"left", TurnIndicatorsCommand::ENABLE_LEFT},
{"right", TurnIndicatorsCommand::ENABLE_RIGHT},
{"straight", TurnIndicatorsCommand::DISABLE},
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,13 +22,6 @@

#include <autoware_auto_perception_msgs/msg/predicted_objects.hpp>
#include <geometry_msgs/msg/pose.hpp>
#include <geometry_msgs/msg/vector3.hpp>

#include <boost/geometry.hpp>
#include <boost/geometry/algorithms/intersection.hpp>
#include <boost/geometry/algorithms/overlaps.hpp>
#include <boost/geometry/index/predicates.hpp>
#include <boost/geometry/index/rtree.hpp>

namespace drivable_area_expansion
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@

#include <interpolation/linear_interpolation.hpp>

#include <boost/geometry.hpp>
#include <boost/geometry/algorithms/distance.hpp>

#include <limits>

Expand Down Expand Up @@ -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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,18 +41,18 @@ using tier4_autoware_utils::Point2d;
using tier4_autoware_utils::Polygon2d;
using tier4_autoware_utils::Segment2d;

typedef boost::geometry::index::rtree<Segment2d, boost::geometry::index::rstar<16>> SegmentRtree;
using SegmentRtree = boost::geometry::index::rtree<Segment2d, boost::geometry::index::rstar<16>>;

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 };

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,14 +21,6 @@
#include <geometry_msgs/msg/pose_array.hpp>
#include <nav_msgs/msg/occupancy_grid.hpp>

#include <tf2/utils.h>

#ifdef ROS_DISTRO_GALACTIC
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#else
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
#endif

#include <vector>

namespace behavior_path_planner
Expand Down Expand Up @@ -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
Expand All @@ -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);
Expand All @@ -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<IndexXY> & indexes);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,8 +17,6 @@

#include "behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp"

#include <rclcpp/rclcpp.hpp>

#include <autoware_auto_perception_msgs/msg/predicted_objects.hpp>

#include <vector>
Expand Down
Loading

0 comments on commit 9855c95

Please sign in to comment.