Skip to content

Commit

Permalink
refactor(lane_change): use lane change namespace for structs (autowar…
Browse files Browse the repository at this point in the history
…efoundation#7508)

* refactor(lane_change): use lane change namespace for structs

Signed-off-by: Zulfaqar Azmi <[email protected]>

* Move lane change namespace to bottom level

Signed-off-by: Zulfaqar Azmi <[email protected]>

---------

Signed-off-by: Zulfaqar Azmi <[email protected]>
Signed-off-by: Muhammad Zulfaqar Azmi <[email protected]>
  • Loading branch information
zulfaqar-azmi-t4 committed Aug 6, 2024
1 parent 73ed8b8 commit bb2330c
Show file tree
Hide file tree
Showing 6 changed files with 11 additions and 18 deletions.
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 @@ -39,10 +39,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 @@ -130,7 +130,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 @@ -242,7 +242,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 @@ -190,13 +190,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 @@ -211,7 +204,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 @@ -225,6 +218,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

0 comments on commit bb2330c

Please sign in to comment.