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(lane_change): use lane change namespace for structs #7508

Merged
Show file tree
Hide file tree
Changes from all 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 @@ -31,10 +31,10 @@ using autoware::behavior_path_planner::utils::path_safety_checker::
using autoware::behavior_path_planner::utils::path_safety_checker::PoseWithVelocityStamped;
using autoware::behavior_path_planner::utils::path_safety_checker::PredictedPathWithPolygon;
using autoware::route_handler::Direction;
using data::lane_change::LanesPolygon;
using geometry_msgs::msg::Point;
using geometry_msgs::msg::Pose;
using geometry_msgs::msg::Twist;
using lane_change::LanesPolygon;
using tier4_planning_msgs::msg::PathWithLaneId;
using utils::path_safety_checker::ExtendedPredictedObjects;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,10 +38,10 @@ namespace autoware::behavior_path_planner
{
using autoware::route_handler::Direction;
using autoware::universe_utils::StopWatch;
using data::lane_change::PathSafetyStatus;
using geometry_msgs::msg::Point;
using geometry_msgs::msg::Pose;
using geometry_msgs::msg::Twist;
using lane_change::PathSafetyStatus;
using tier4_planning_msgs::msg::PathWithLaneId;

class LaneChangeBase
Expand Down Expand Up @@ -126,7 +126,7 @@ class LaneChangeBase

const LaneChangeStatus & getLaneChangeStatus() const { return status_; }

const data::lane_change::Debug & getDebugData() const { return lane_change_debug_; }
const lane_change::Debug & getDebugData() const { return lane_change_debug_; }

const Pose & getEgoPose() const { return planner_data_->self_odometry->pose.pose; }

Expand Down Expand Up @@ -233,7 +233,7 @@ class LaneChangeBase
LaneChangeModuleType type_{LaneChangeModuleType::NORMAL};

mutable StopWatch<std::chrono::milliseconds> stop_watch_;
mutable data::lane_change::Debug lane_change_debug_;
mutable lane_change::Debug lane_change_debug_;

rclcpp::Logger logger_ = utils::lane_change::getLogger(getModuleTypeStr());
mutable rclcpp::Clock clock_{RCL_ROS_TIME};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -189,13 +189,6 @@ struct LaneChangeInfo
double terminal_lane_changing_velocity{0.0};
};

struct LaneChangeTargetObjectIndices
{
std::vector<size_t> current_lane{};
std::vector<size_t> target_lane{};
std::vector<size_t> other_lane{};
};

struct LaneChangeLanesFilteredObjects
{
utils::path_safety_checker::ExtendedPredictedObjects current_lane{};
Expand All @@ -210,7 +203,7 @@ enum class LaneChangeModuleType {
};
} // namespace autoware::behavior_path_planner

namespace autoware::behavior_path_planner::data::lane_change
namespace autoware::behavior_path_planner::lane_change
{
struct PathSafetyStatus
{
Expand All @@ -224,6 +217,6 @@ struct LanesPolygon
std::optional<lanelet::BasicPolygon2d> target;
std::vector<lanelet::BasicPolygon2d> target_backward;
};
} // namespace autoware::behavior_path_planner::data::lane_change
} // namespace autoware::behavior_path_planner::lane_change

#endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__DATA_STRUCTS_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@
#include <limits>
#include <string>

namespace autoware::behavior_path_planner::data::lane_change
namespace autoware::behavior_path_planner::lane_change
{
using utils::path_safety_checker::CollisionCheckDebugMap;
struct Debug
Expand Down Expand Up @@ -71,6 +71,6 @@ struct Debug
is_abort = false;
}
};
} // namespace autoware::behavior_path_planner::data::lane_change
} // namespace autoware::behavior_path_planner::lane_change

#endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__DEBUG_STRUCTS_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@
namespace marker_utils::lane_change_markers
{
using autoware::behavior_path_planner::LaneChangePath;
using autoware::behavior_path_planner::data::lane_change::Debug;
using autoware::behavior_path_planner::lane_change::Debug;
using autoware::behavior_path_planner::utils::path_safety_checker::ExtendedPredictedObjects;
using visualization_msgs::msg::MarkerArray;
MarkerArray showAllValidLaneChangePath(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -48,8 +48,8 @@ using autoware::universe_utils::Polygon2d;
using autoware_perception_msgs::msg::PredictedObject;
using autoware_perception_msgs::msg::PredictedObjects;
using autoware_perception_msgs::msg::PredictedPath;
using data::lane_change::LanesPolygon;
using data::lane_change::PathSafetyStatus;
using behavior_path_planner::lane_change::LanesPolygon;
using behavior_path_planner::lane_change::PathSafetyStatus;
using geometry_msgs::msg::Point;
using geometry_msgs::msg::Pose;
using geometry_msgs::msg::Twist;
Expand Down
Loading