Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

refactor(avoidance): remove unused header #5907

Merged
Show file tree
Hide file tree
Changes from 3 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -19,12 +19,11 @@
#include "behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp"
#include "behavior_path_planner_common/utils/path_shifter/path_shifter.hpp"

#include <rclcpp/rclcpp.hpp>
#include <rclcpp/time.hpp>
#include <tier4_autoware_utils/geometry/boost_geometry.hpp>

#include <autoware_auto_perception_msgs/msg/predicted_objects.hpp>
#include <autoware_auto_planning_msgs/msg/path_with_lane_id.hpp>
#include <geometry_msgs/msg/transform_stamped.hpp>
#include <tier4_planning_msgs/msg/avoidance_debug_msg_array.hpp>

#include <lanelet2_core/primitives/Lanelet.h>
Expand All @@ -34,6 +33,7 @@
#include <memory>
#include <string>
#include <unordered_map>
#include <utility>
#include <vector>

namespace behavior_path_planner
Expand All @@ -48,7 +48,6 @@

using geometry_msgs::msg::Point;
using geometry_msgs::msg::Pose;
using geometry_msgs::msg::TransformStamped;

using behavior_path_planner::utils::path_safety_checker::CollisionCheckDebug;

Expand Down Expand Up @@ -326,24 +325,24 @@
struct ObjectData // avoidance target
{
ObjectData() = default;
ObjectData(const PredictedObject & obj, double lat, double lon, double len, double overhang)
: object(obj), lateral(lat), longitudinal(lon), length(len), overhang_dist(overhang)
ObjectData(PredictedObject obj, double lat, double lon, double len, double overhang)
: object(std::move(obj)), lateral(lat), longitudinal(lon), length(len), overhang_dist(overhang)
{
}

PredictedObject object;

// lateral position of the CoM, in Frenet coordinate from ego-pose
double lateral;
double lateral{0.0};

// longitudinal position of the CoM, in Frenet coordinate from ego-pose
double longitudinal;
double longitudinal{0.0};

// longitudinal length of vehicle, in Frenet coordinate
double length;
double length{0.0};

// lateral distance to the closest footprint, in Frenet coordinate
double overhang_dist;
double overhang_dist{0.0};

// lateral shiftable ratio
double shiftable_ratio{0.0};
Expand Down Expand Up @@ -397,7 +396,7 @@
bool is_within_intersection{false};

// unavoidable reason
std::string reason{""};
std::string reason{};

// lateral avoid margin
std::optional<double> avoid_margin{std::nullopt};
Expand Down Expand Up @@ -440,8 +439,8 @@

struct AvoidOutline
{
AvoidOutline(const AvoidLine & avoid_line, const AvoidLine & return_line)
: avoid_line{avoid_line}, return_line{return_line}
AvoidOutline(AvoidLine avoid_line, AvoidLine return_line)

Check warning on line 442 in planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/data_structs.hpp#L442

Added line #L442 was not covered by tests
: avoid_line{std::move(avoid_line)}, return_line{std::move(return_line)}
{
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,41 +16,31 @@
#define BEHAVIOR_PATH_AVOIDANCE_MODULE__DEBUG_HPP_

#include "behavior_path_avoidance_module/data_structs.hpp"
#include "behavior_path_planner_common/marker_utils/utils.hpp"

#include <tier4_autoware_utils/ros/marker_helper.hpp>

#include <autoware_auto_perception_msgs/msg/predicted_objects.hpp>
#include <autoware_auto_planning_msgs/msg/path_with_lane_id.hpp>
#include <geometry_msgs/msg/polygon.hpp>
#include <visualization_msgs/msg/marker_array.hpp>

#include <lanelet2_core/Forward.h>

#include <string>
#include <vector>

namespace marker_utils::avoidance_marker
{
using autoware_auto_perception_msgs::msg::PredictedObjects;
using autoware_auto_planning_msgs::msg::PathWithLaneId;
using behavior_path_planner::AvoidancePlanningData;
using behavior_path_planner::AvoidanceState;
using behavior_path_planner::AvoidLineArray;
using behavior_path_planner::DebugData;
using behavior_path_planner::ObjectDataArray;
using behavior_path_planner::PathShifter;
using behavior_path_planner::ShiftLineArray;
using geometry_msgs::msg::Point;
using geometry_msgs::msg::Polygon;
using geometry_msgs::msg::Pose;
using visualization_msgs::msg::MarkerArray;

MarkerArray createEgoStatusMarkerArray(
const AvoidancePlanningData & data, const Pose & p_ego, std::string && ns);

MarkerArray createAvoidLineMarkerArray(
const AvoidLineArray & shift_points, std::string && ns, const float & r, const float & g,
const AvoidLineArray & shift_lines, std::string && ns, const float & r, const float & g,
const float & b, const double & w);

MarkerArray createPredictedVehiclePositions(const PathWithLaneId & path, std::string && ns);
Expand All @@ -63,11 +53,11 @@ MarkerArray createDebugMarkerArray(
const AvoidancePlanningData & data, const PathShifter & shifter, const DebugData & debug);
} // namespace marker_utils::avoidance_marker

std::string toStrInfo(const behavior_path_planner::ShiftLineArray & sp_arr);
std::string toStrInfo(const behavior_path_planner::ShiftLineArray & sl_arr);

std::string toStrInfo(const behavior_path_planner::AvoidLineArray & ap_arr);

std::string toStrInfo(const behavior_path_planner::ShiftLine & sp);
std::string toStrInfo(const behavior_path_planner::ShiftLine & sl);

std::string toStrInfo(const behavior_path_planner::AvoidLine & ap);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ class AvoidanceHelper

geometry_msgs::msg::Pose getEgoPose() const { return data_->self_odometry->pose.pose; }

size_t getConstraintsMapIndex(const double velocity, const std::vector<double> & values) const
static size_t getConstraintsMapIndex(const double velocity, const std::vector<double> & values)
{
const auto itr = std::find_if(
values.begin(), values.end(), [&](const auto value) { return velocity < value; });
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,11 +19,10 @@
#include "behavior_path_avoidance_module/scene.hpp"
#include "behavior_path_planner_common/interface/scene_module_manager_interface.hpp"

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

#include <memory>
#include <string>
#include <unordered_map>
#include <vector>

namespace behavior_path_planner
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,21 +20,20 @@
#include "behavior_path_avoidance_module/shift_line_generator.hpp"
#include "behavior_path_planner_common/interface/scene_module_interface.hpp"
#include "behavior_path_planner_common/interface/scene_module_visitor.hpp"
#include "behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp"

#include <rclcpp/rclcpp.hpp>
#include <rclcpp/logging.hpp>
#include <rclcpp/node.hpp>
#include <rclcpp/time.hpp>

#include <autoware_auto_perception_msgs/msg/predicted_object.hpp>
#include <autoware_auto_planning_msgs/msg/path_with_lane_id.hpp>
#include <autoware_auto_vehicle_msgs/msg/turn_indicators_command.hpp>
#include <tier4_planning_msgs/msg/avoidance_debug_msg.hpp>
#include <tier4_planning_msgs/msg/avoidance_debug_msg_array.hpp>

#include <algorithm>
#include <memory>
#include <string>
#include <unordered_map>
#include <utility>
#include <vector>

namespace behavior_path_planner
Expand Down Expand Up @@ -374,8 +373,8 @@
*/
void removeRegisteredShiftLines()
{
constexpr double THRESHOLD = 0.1;
if (std::abs(path_shifter_.getBaseOffset()) > THRESHOLD) {
constexpr double threshold = 0.1;
if (std::abs(path_shifter_.getBaseOffset()) > threshold) {
RCLCPP_INFO(getLogger(), "base offset is not zero. can't reset registered shift lines.");
return;
}
Expand All @@ -396,7 +395,7 @@
* @brief remove behind shift lines.
* @param path shifter.
*/
void postProcess()
void postProcess() override

Check warning on line 398 in planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/scene.hpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/scene.hpp#L398

Added line #L398 was not covered by tests
{
const size_t idx = planner_data_->findEgoIndex(path_shifter_.getReferencePath().points);
path_shifter_.removeBehindShiftLineAndSetBaseOffset(idx);
Expand All @@ -411,8 +410,6 @@

using RegisteredShiftLineArray = std::vector<RegisteredShiftLine>;

bool is_avoidance_maneuver_starts;

bool arrived_path_end_{false};

bool safe_{true};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,20 +17,15 @@

#include "behavior_path_avoidance_module/data_structs.hpp"
#include "behavior_path_avoidance_module/helper.hpp"
#include "behavior_path_planner_common/data_manager.hpp"
#include "behavior_path_planner_common/utils/path_shifter/path_shifter.hpp"

#include <rclcpp/rclcpp.hpp>

#include <memory>

namespace behavior_path_planner::utils::avoidance
{

using behavior_path_planner::PathShifter;
using behavior_path_planner::helper::avoidance::AvoidanceHelper;
using motion_utils::calcSignedArcLength;
using motion_utils::findNearestIndex;

class ShiftLineGenerator
{
Expand Down
1 change: 0 additions & 1 deletion planning/behavior_path_avoidance_module/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,6 @@
<depend>behavior_path_planner_common</depend>
<depend>geometry_msgs</depend>
<depend>lanelet2_extension</depend>
<depend>libboost-dev</depend>
<depend>magic_enum</depend>
<depend>motion_utils</depend>
<depend>objects_of_interest_marker_interface</depend>
Expand Down
4 changes: 1 addition & 3 deletions planning/behavior_path_avoidance_module/src/debug.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,16 +14,14 @@

#include "behavior_path_avoidance_module/debug.hpp"

#include "behavior_path_planner_common/marker_utils/utils.hpp"
#include "behavior_path_planner_common/utils/utils.hpp"

#include <magic_enum.hpp>
#include <tier4_autoware_utils/ros/uuid_helper.hpp>

#include <tier4_planning_msgs/msg/avoidance_debug_factor.hpp>

#include <lanelet2_core/primitives/LineString.h>
#include <tf2/utils.h>

#include <string>
#include <vector>

Expand Down
13 changes: 5 additions & 8 deletions planning/behavior_path_avoidance_module/src/scene.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2023 TIER IV, Inc.

Check notice on line 1 in planning/behavior_path_avoidance_module/src/scene.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Lines of Code in a Single File

The lines of code decreases from 1195 to 1194, improve code health by reducing it to 1000. The number of Lines of Code in a single file. More Lines of Code lowers the code health.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand All @@ -20,6 +20,7 @@
#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/path_safety_checker/objects_filtering.hpp"
#include "behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp"
#include "behavior_path_planner_common/utils/path_utils.hpp"
#include "behavior_path_planner_common/utils/utils.hpp"

Expand All @@ -28,14 +29,11 @@
#include <tier4_autoware_utils/geometry/boost_polygon_utils.hpp>
#include <tier4_autoware_utils/geometry/geometry.hpp>
#include <tier4_autoware_utils/ros/marker_helper.hpp>
#include <tier4_autoware_utils/ros/uuid_helper.hpp>

#include <tier4_planning_msgs/msg/avoidance_debug_factor.hpp>
#include <tier4_planning_msgs/msg/avoidance_debug_msg.hpp>
#include <tier4_planning_msgs/msg/avoidance_debug_msg_array.hpp>
#include "tier4_planning_msgs/msg/detail/avoidance_debug_msg_array__struct.hpp"
#include <tier4_planning_msgs/msg/detail/avoidance_debug_factor__struct.hpp>

#include <boost/geometry/algorithms/centroid.hpp>
#include <boost/geometry/strategies/cartesian/centroid_bashein_detmer.hpp>

#include <algorithm>
#include <limits>
Expand Down Expand Up @@ -1229,7 +1227,6 @@
debug_marker_.markers.clear();
resetPathCandidate();
resetPathReference();
is_avoidance_maneuver_starts = false;
arrived_path_end_ = false;
}

Expand Down Expand Up @@ -1266,8 +1263,8 @@

CandidateOutput output;

const auto sl_front = candidates.front();
const auto sl_back = candidates.back();
const auto & sl_front = candidates.front();
const auto & sl_back = candidates.back();

output.path_candidate = data.candidate_path.path;
output.lateral_shift = helper_->getRelativeShiftToPath(shift_line);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@

#include <tier4_autoware_utils/ros/uuid_helper.hpp>

#include <tier4_planning_msgs/msg/avoidance_debug_factor.hpp>
#include <tier4_planning_msgs/msg/detail/avoidance_debug_factor__struct.hpp>

namespace behavior_path_planner::utils::avoidance
{
Expand Down
14 changes: 4 additions & 10 deletions planning/behavior_path_avoidance_module/src/utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,29 +21,23 @@
#include "behavior_path_planner_common/utils/traffic_light_utils.hpp"
#include "tier4_autoware_utils/geometry/boost_polygon_utils.hpp"

#include <autoware_auto_tf2/tf2_autoware_auto_msgs.hpp>
#include <lanelet2_extension/utility/utilities.hpp>
#include <motion_utils/trajectory/interpolation.hpp>
#include <tier4_autoware_utils/geometry/geometry.hpp>
#include <tier4_autoware_utils/math/unit_conversion.hpp>
#include <tier4_autoware_utils/ros/uuid_helper.hpp>

#include <tier4_planning_msgs/msg/avoidance_debug_factor.hpp>
#include <geometry_msgs/msg/detail/transform_stamped__struct.hpp>
#include <tier4_planning_msgs/msg/detail/avoidance_debug_factor__struct.hpp>

#include <boost/geometry.hpp>
#include <boost/geometry/algorithms/buffer.hpp>
#include <boost/geometry/algorithms/convex_hull.hpp>
#include <boost/geometry/algorithms/correct.hpp>
#include <boost/geometry/algorithms/union.hpp>
#include <boost/geometry/geometries/geometries.hpp>
#include <boost/geometry/geometries/point_xy.hpp>
#include <boost/geometry/strategies/convex_hull.hpp>

#include <lanelet2_routing/RoutingGraphContainer.h>

#include <algorithm>
#include <limits>
#include <memory>
#include <set>
#include <string>
#include <vector>

Expand All @@ -53,6 +47,7 @@ namespace behavior_path_planner::utils::avoidance
using autoware_perception_msgs::msg::TrafficSignalElement;
using behavior_path_planner::utils::traffic_light::calcDistanceToRedTrafficLight;
using behavior_path_planner::utils::traffic_light::getDistanceToNextTrafficLight;
using geometry_msgs::msg::TransformStamped;
using motion_utils::calcLongitudinalOffsetPoint;
using motion_utils::calcSignedArcLength;
using motion_utils::findNearestIndex;
Expand All @@ -65,7 +60,6 @@ using tier4_autoware_utils::calcYawDeviation;
using tier4_autoware_utils::createQuaternionFromRPY;
using tier4_autoware_utils::getPose;
using tier4_autoware_utils::pose2transform;
using tier4_autoware_utils::toHexString;
using tier4_planning_msgs::msg::AvoidanceDebugFactor;
using tier4_planning_msgs::msg::AvoidanceDebugMsg;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,9 +17,6 @@
#include "planning_interface_test_manager/planning_interface_test_manager.hpp"
#include "planning_interface_test_manager/planning_interface_test_manager_utils.hpp"

#include <gtest/gtest.h>

#include <cmath>
#include <vector>

using behavior_path_planner::BehaviorPathPlannerNode;
Expand Down
Loading