Skip to content

Commit

Permalink
refactor(route_handler): route handler add autoware prefix (#7341)
Browse files Browse the repository at this point in the history
* rename route handler package

Signed-off-by: mohammad alqudah <[email protected]>

* update packages dependencies

Signed-off-by: mohammad alqudah <[email protected]>

* update include guards

Signed-off-by: mohammad alqudah <[email protected]>

* update includes

Signed-off-by: mohammad alqudah <[email protected]>

* put in autoware namespace

Signed-off-by: mohammad alqudah <[email protected]>

* fix formats

Signed-off-by: mohammad alqudah <[email protected]>

* keep header and source file name as before

Signed-off-by: mohammad alqudah <[email protected]>

---------

Signed-off-by: mohammad alqudah <[email protected]>
  • Loading branch information
mkquda authored Jun 11, 2024
1 parent bf81712 commit 4129ddd
Show file tree
Hide file tree
Showing 74 changed files with 107 additions and 106 deletions.
2 changes: 1 addition & 1 deletion .github/CODEOWNERS
Validating CODEOWNERS rules …
Original file line number Diff line number Diff line change
Expand Up @@ -196,7 +196,7 @@ planning/obstacle_velocity_limiter/** [email protected]
planning/autoware_path_smoother/** [email protected] [email protected]
planning/planning_test_utils/** [email protected] [email protected] [email protected] [email protected]
planning/planning_validator/** [email protected] [email protected]
planning/route_handler/** [email protected] [email protected] [email protected] [email protected] [email protected] [email protected]
planning/autoware_route_handler/** [email protected] [email protected] [email protected] [email protected] [email protected] [email protected]
planning/rtc_interface/** [email protected] [email protected] [email protected] [email protected]
planning/rtc_replayer/** [email protected] [email protected]
planning/sampling_based_planner/autoware_bezier_sampler/** [email protected]
Expand Down
2 changes: 1 addition & 1 deletion planning/.pages
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,7 @@ nav:
- 'Costmap Generator': planning/costmap_generator
- 'External Velocity Limit Selector': planning/autoware_external_velocity_limit_selector
- 'Objects of Interest Marker Interface': planning/autoware_objects_of_interest_marker_interface
- 'Route Handler': planning/route_handler
- 'Route Handler': planning/autoware_route_handler
- 'RTC Interface': planning/autoware_rtc_interface
- 'Additional Tools':
- 'Remaining Distance Time Calculator': planning/autoware_remaining_distance_time_calculator
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,8 @@

namespace autoware::behavior_path_planner
{
using autoware::route_handler::Direction;
using ::behavior_path_planner::State;
using ::route_handler::Direction;

AvoidanceByLaneChangeInterface::AvoidanceByLaneChangeInterface(
const std::string & name, rclcpp::Node & node,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,14 +31,13 @@ namespace autoware::behavior_path_planner
using ::behavior_path_planner::LaneChangeModuleManager;
using ::behavior_path_planner::LaneChangeModuleType;
using ::behavior_path_planner::SceneModuleInterface;
using ::route_handler::Direction;

class AvoidanceByLaneChangeModuleManager : public LaneChangeModuleManager
{
public:
AvoidanceByLaneChangeModuleManager()
: LaneChangeModuleManager(
"avoidance_by_lane_change", route_handler::Direction::NONE,
"avoidance_by_lane_change", autoware::route_handler::Direction::NONE,
LaneChangeModuleType::AVOIDANCE_BY_LANE_CHANGE)
{
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@
#define MANAGER_HPP_

#include "autoware_behavior_path_lane_change_module/manager.hpp"
#include "route_handler/route_handler.hpp"
#include "autoware_route_handler/route_handler.hpp"

#include <rclcpp/rclcpp.hpp>

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

#include "autoware_behavior_path_lane_change_module/utils/data_structs.hpp"
#include "autoware_behavior_path_planner_common/interface/scene_module_manager_interface.hpp"
#include "route_handler/route_handler.hpp"
#include "autoware_route_handler/route_handler.hpp"

#include <rclcpp/rclcpp.hpp>

Expand All @@ -27,7 +27,7 @@

namespace behavior_path_planner
{
using route_handler::Direction;
using autoware::route_handler::Direction;

class LaneChangeModuleManager : public SceneModuleManagerInterface
{
Expand Down Expand Up @@ -58,8 +58,7 @@ class LaneChangeRightModuleManager : public LaneChangeModuleManager
{
public:
LaneChangeRightModuleManager()
: LaneChangeModuleManager(
"lane_change_right", route_handler::Direction::RIGHT, LaneChangeModuleType::NORMAL)
: LaneChangeModuleManager("lane_change_right", Direction::RIGHT, LaneChangeModuleType::NORMAL)
{
}
};
Expand All @@ -68,8 +67,7 @@ class LaneChangeLeftModuleManager : public LaneChangeModuleManager
{
public:
LaneChangeLeftModuleManager()
: LaneChangeModuleManager(
"lane_change_left", route_handler::Direction::LEFT, LaneChangeModuleType::NORMAL)
: LaneChangeModuleManager("lane_change_left", Direction::LEFT, LaneChangeModuleType::NORMAL)
{
}
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@

namespace behavior_path_planner
{
using autoware::route_handler::Direction;
using behavior_path_planner::utils::path_safety_checker::CollisionCheckDebug;
using behavior_path_planner::utils::path_safety_checker::CollisionCheckDebugMap;
using behavior_path_planner::utils::path_safety_checker::ExtendedPredictedObject;
Expand All @@ -33,7 +34,6 @@ using data::lane_change::LanesPolygon;
using geometry_msgs::msg::Point;
using geometry_msgs::msg::Pose;
using geometry_msgs::msg::Twist;
using route_handler::Direction;
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 @@ -36,11 +36,11 @@

namespace behavior_path_planner
{
using autoware::route_handler::Direction;
using data::lane_change::PathSafetyStatus;
using geometry_msgs::msg::Point;
using geometry_msgs::msg::Pose;
using geometry_msgs::msg::Twist;
using route_handler::Direction;
using tier4_autoware_utils::StopWatch;
using tier4_planning_msgs::msg::PathWithLaneId;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
#include "autoware_behavior_path_planner_common/utils/utils.hpp"
#include "rclcpp/logger.hpp"

#include <route_handler/route_handler.hpp>
#include <autoware_route_handler/route_handler.hpp>
#include <tier4_autoware_utils/geometry/boost_geometry.hpp>

#include <autoware_perception_msgs/msg/predicted_objects.hpp>
Expand All @@ -38,6 +38,7 @@

namespace behavior_path_planner::utils::lane_change
{
using autoware::route_handler::Direction;
using autoware_perception_msgs::msg::PredictedObject;
using autoware_perception_msgs::msg::PredictedObjects;
using autoware_perception_msgs::msg::PredictedPath;
Expand All @@ -51,7 +52,6 @@ using geometry_msgs::msg::Point;
using geometry_msgs::msg::Pose;
using geometry_msgs::msg::Twist;
using path_safety_checker::CollisionCheckDebugMap;
using route_handler::Direction;
using tier4_autoware_utils::Polygon2d;
using tier4_planning_msgs::msg::PathWithLaneId;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -57,10 +57,10 @@

namespace behavior_path_planner::utils::lane_change
{
using autoware::route_handler::RouteHandler;
using autoware_perception_msgs::msg::ObjectClassification;
using autoware_perception_msgs::msg::PredictedObjects;
using geometry_msgs::msg::Pose;
using route_handler::RouteHandler;
using tier4_autoware_utils::LineString2d;
using tier4_autoware_utils::Point2d;
using tier4_autoware_utils::Polygon2d;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,11 +20,11 @@
#include "autoware_behavior_path_planner_common/utils/drivable_area_expansion/parameters.hpp"
#include "motion_utils/trajectory/trajectory.hpp"

#include <autoware_route_handler/route_handler.hpp>
#include <lanelet2_extension/regulatory_elements/Forward.hpp>
#include <lanelet2_extension/utility/utilities.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>
#include <autoware_perception_msgs/msg/predicted_objects.hpp>
Expand All @@ -50,6 +50,7 @@

namespace behavior_path_planner
{
using autoware::route_handler::RouteHandler;
using autoware_adapi_v1_msgs::msg::OperationModeState;
using autoware_perception_msgs::msg::PredictedObject;
using autoware_perception_msgs::msg::PredictedObjects;
Expand All @@ -61,7 +62,6 @@ using geometry_msgs::msg::AccelWithCovarianceStamped;
using geometry_msgs::msg::PoseStamped;
using nav_msgs::msg::OccupancyGrid;
using nav_msgs::msg::Odometry;
using route_handler::RouteHandler;
using tier4_planning_msgs::msg::LateralOffset;
using tier4_planning_msgs::msg::PathWithLaneId;
using PlanResult = PathWithLaneId::SharedPtr;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,13 +23,13 @@
#include <autoware_behavior_path_planner_common/interface/steering_factor_interface.hpp>
#include <autoware_behavior_path_planner_common/turn_signal_decider.hpp>
#include <autoware_objects_of_interest_marker_interface/objects_of_interest_marker_interface.hpp>
#include <autoware_route_handler/route_handler.hpp>
#include <autoware_rtc_interface/rtc_interface.hpp>
#include <magic_enum.hpp>
#include <motion_utils/marker/marker_helper.hpp>
#include <motion_utils/trajectory/path_with_lane_id.hpp>
#include <motion_utils/trajectory/trajectory.hpp>
#include <rclcpp/rclcpp.hpp>
#include <route_handler/route_handler.hpp>
#include <tier4_autoware_utils/geometry/geometry.hpp>
#include <tier4_autoware_utils/ros/marker_helper.hpp>
#include <tier4_autoware_utils/ros/uuid_helper.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,8 +19,8 @@

#include <autoware_behavior_path_planner_common/parameters.hpp>
#include <autoware_behavior_path_planner_common/utils/path_shifter/path_shifter.hpp>
#include <autoware_route_handler/route_handler.hpp>
#include <lanelet2_extension/utility/message_conversion.hpp>
#include <route_handler/route_handler.hpp>
#include <tier4_autoware_utils/geometry/boost_geometry.hpp>
#include <tier4_autoware_utils/geometry/geometry.hpp>

Expand All @@ -42,12 +42,12 @@

namespace behavior_path_planner
{
using autoware::route_handler::RouteHandler;
using autoware_vehicle_msgs::msg::HazardLightsCommand;
using autoware_vehicle_msgs::msg::TurnIndicatorsCommand;
using geometry_msgs::msg::Point;
using geometry_msgs::msg::Pose;
using nav_msgs::msg::Odometry;
using route_handler::RouteHandler;
using tier4_planning_msgs::msg::PathWithLaneId;

const std::map<std::string, uint8_t> g_signal_map = {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@
#include "autoware_behavior_path_planner_common/utils/drivable_area_expansion/parameters.hpp"
#include "autoware_behavior_path_planner_common/utils/drivable_area_expansion/types.hpp"

#include <route_handler/route_handler.hpp>
#include <autoware_route_handler/route_handler.hpp>

#include <lanelet2_core/Forward.h>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
#include "autoware_behavior_path_planner_common/data_manager.hpp"
#include "motion_utils/trajectory/trajectory.hpp"

#include <route_handler/route_handler.hpp>
#include <autoware_route_handler/route_handler.hpp>
#include <tier4_autoware_utils/geometry/boost_geometry.hpp>

#include <autoware_perception_msgs/msg/object_classification.hpp>
Expand Down Expand Up @@ -46,10 +46,10 @@ using autoware_perception_msgs::msg::PredictedObject;
using autoware_perception_msgs::msg::PredictedObjects;
using autoware_perception_msgs::msg::PredictedPath;

using autoware::route_handler::RouteHandler;
using geometry_msgs::msg::Point;
using geometry_msgs::msg::Pose;
using geometry_msgs::msg::Vector3;
using route_handler::RouteHandler;
using tier4_autoware_utils::LinearRing2d;
using tier4_autoware_utils::Polygon2d;
using tier4_planning_msgs::msg::PathPointWithLaneId;
Expand Down Expand Up @@ -327,7 +327,7 @@ lanelet::ConstLanelets calcLaneAroundPose(
bool checkPathRelativeAngle(const PathWithLaneId & path, const double angle_threshold);

lanelet::ConstLanelets getLaneletsFromPath(
const PathWithLaneId & path, const std::shared_ptr<route_handler::RouteHandler> & route_handler);
const PathWithLaneId & path, const std::shared_ptr<RouteHandler> & route_handler);

std::string convertToSnakeCase(const std::string & input_str);

Expand Down
2 changes: 1 addition & 1 deletion planning/autoware_behavior_path_planner_common/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,7 @@
<depend>autoware_objects_of_interest_marker_interface</depend>
<depend>autoware_perception_msgs</depend>
<depend>autoware_planning_msgs</depend>
<depend>autoware_route_handler</depend>
<depend>autoware_rtc_interface</depend>
<depend>autoware_vehicle_info_utils</depend>
<depend>geometry_msgs</depend>
Expand All @@ -57,7 +58,6 @@
<depend>motion_utils</depend>
<depend>object_recognition_utils</depend>
<depend>rclcpp</depend>
<depend>route_handler</depend>
<depend>tf2</depend>
<depend>tier4_autoware_utils</depend>
<depend>tier4_planning_msgs</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -1607,7 +1607,7 @@ bool checkPathRelativeAngle(const PathWithLaneId & path, const double angle_thre
}

lanelet::ConstLanelets getLaneletsFromPath(
const PathWithLaneId & path, const std::shared_ptr<route_handler::RouteHandler> & route_handler)
const PathWithLaneId & path, const std::shared_ptr<RouteHandler> & route_handler)
{
std::vector<int64_t> unique_lanelet_ids;
for (const auto & p : path.points) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -179,7 +179,7 @@ TEST(DrivableAreaExpansionProjection, expand_drivable_area)
autoware_map_msgs::msg::LaneletMapBin map;
lanelet::LaneletMapPtr empty_lanelet_map_ptr = std::make_shared<lanelet::LaneletMap>();
lanelet::utils::conversion::toBinMsg(empty_lanelet_map_ptr, &map);
route_handler::RouteHandler route_handler(map);
autoware::route_handler::RouteHandler route_handler(map);
lanelet::ConstLanelets path_lanes = {};
drivable_area_expansion::PathWithLaneId path;
{ // Simple path with Y=0 and X = 0, 1, 2
Expand Down Expand Up @@ -228,7 +228,8 @@ TEST(DrivableAreaExpansionProjection, expand_drivable_area)
planner_data.dynamic_object =
std::make_shared<drivable_area_expansion::PredictedObjects>(dynamic_objects);
planner_data.self_odometry = std::make_shared<nav_msgs::msg::Odometry>();
planner_data.route_handler = std::make_shared<route_handler::RouteHandler>(route_handler);
planner_data.route_handler =
std::make_shared<autoware::route_handler::RouteHandler>(route_handler);
drivable_area_expansion::expand_drivable_area(
path, std::make_shared<behavior_path_planner::PlannerData>(planner_data));
// unchanged path points
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@
#include "autoware_behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp"
#include "autoware_behavior_path_start_planner_module/pull_out_path.hpp"

#include <route_handler/route_handler.hpp>
#include <autoware_route_handler/route_handler.hpp>

#include <autoware_perception_msgs/msg/predicted_objects.hpp>
#include <autoware_perception_msgs/msg/predicted_path.hpp>
Expand All @@ -36,12 +36,12 @@

namespace behavior_path_planner::start_planner_utils
{
using autoware::route_handler::RouteHandler;
using autoware_perception_msgs::msg::PredictedObjects;
using autoware_perception_msgs::msg::PredictedPath;
using behavior_path_planner::utils::path_safety_checker::EgoPredictedPathParams;
using geometry_msgs::msg::Pose;
using geometry_msgs::msg::Twist;
using route_handler::RouteHandler;
using tier4_planning_msgs::msg::PathWithLaneId;

PathWithLaneId getBackwardPath(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,8 +35,8 @@
namespace behavior_path_planner
{

using autoware::route_handler::Direction;
using behavior_path_planner::utils::path_safety_checker::CollisionCheckDebug;
using route_handler::Direction;

enum class ObjectInfo {
NONE = 0,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@
<depend>autoware_behavior_path_planner_common</depend>
<depend>autoware_objects_of_interest_marker_interface</depend>
<depend>autoware_perception_msgs</depend>
<depend>autoware_route_handler</depend>
<depend>autoware_rtc_interface</depend>
<depend>autoware_vehicle_info_utils</depend>
<depend>behavior_path_planner</depend>
Expand All @@ -33,7 +34,6 @@
<depend>motion_utils</depend>
<depend>pluginlib</depend>
<depend>rclcpp</depend>
<depend>route_handler</depend>
<depend>sensor_msgs</depend>
<depend>signal_processing</depend>
<depend>tf2</depend>
Expand Down
Loading

0 comments on commit 4129ddd

Please sign in to comment.