Skip to content

Commit

Permalink
refactor(route_handler)!: rename to include/autoware/{package_name} (a…
Browse files Browse the repository at this point in the history
…utowarefoundation#7530)

refactor(route_handler)!: rename to include/autoware/{package_name}

Signed-off-by: kosuke55 <[email protected]>
  • Loading branch information
kosuke55 authored Jun 17, 2024
1 parent 564e8c1 commit 82a10de
Show file tree
Hide file tree
Showing 26 changed files with 28 additions and 28 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
#endif

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

#include <tf2_ros/buffer.h>
#include <tf2_ros/transform_listener.h>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@
#define LANELET2_PLUGINS__DEFAULT_PLANNER_HPP_

#include <autoware/mission_planner/mission_planner_plugin.hpp>
#include <autoware_route_handler/route_handler.hpp>
#include <autoware/route_handler/route_handler.hpp>
#include <autoware_vehicle_info_utils/vehicle_info_utils.hpp>
#include <rclcpp/rclcpp.hpp>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
#ifndef LANELET2_PLUGINS__UTILITY_FUNCTIONS_HPP_
#define LANELET2_PLUGINS__UTILITY_FUNCTIONS_HPP_

#include <autoware_route_handler/route_handler.hpp>
#include <autoware/route_handler/route_handler.hpp>
#include <autoware_vehicle_info_utils/vehicle_info_utils.hpp>
#include <rclcpp/rclcpp.hpp>
#include <tier4_autoware_utils/geometry/geometry.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@
#include "tier4_autoware_utils/ros/polling_subscriber.hpp"

#include <autoware/mission_planner/mission_planner_plugin.hpp>
#include <autoware_route_handler/route_handler.hpp>
#include <autoware/route_handler/route_handler.hpp>
#include <pluginlib/class_loader.hpp>
#include <rclcpp/rclcpp.hpp>
#include <tier4_autoware_utils/ros/logger_level_configure.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@

#ifndef AUTOWARE_PLANNING_TEST_MANAGER__AUTOWARE_PLANNING_TEST_MANAGER_UTILS_HPP_
#define AUTOWARE_PLANNING_TEST_MANAGER__AUTOWARE_PLANNING_TEST_MANAGER_UTILS_HPP_
#include <autoware_route_handler/route_handler.hpp>
#include <autoware/route_handler/route_handler.hpp>
#include <autoware_test_utils/autoware_test_utils.hpp>

#include <autoware_planning_msgs/msg/lanelet_route.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
#ifndef REMAINING_DISTANCE_TIME_CALCULATOR_NODE_HPP_
#define REMAINING_DISTANCE_TIME_CALCULATOR_NODE_HPP_

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

#include <autoware_internal_msgs/msg/mission_remaining_distance_time.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef AUTOWARE_ROUTE_HANDLER__ROUTE_HANDLER_HPP_
#define AUTOWARE_ROUTE_HANDLER__ROUTE_HANDLER_HPP_
#ifndef AUTOWARE__ROUTE_HANDLER__ROUTE_HANDLER_HPP_
#define AUTOWARE__ROUTE_HANDLER__ROUTE_HANDLER_HPP_

#include <rclcpp/logger.hpp>

Expand Down Expand Up @@ -437,4 +437,4 @@ class RoutingCostDrivable : public lanelet::routing::RoutingCostDistance
}
}; // class RoutingCostDrivable
} // namespace autoware::route_handler
#endif // AUTOWARE_ROUTE_HANDLER__ROUTE_HANDLER_HPP_
#endif // AUTOWARE__ROUTE_HANDLER__ROUTE_HANDLER_HPP_
2 changes: 1 addition & 1 deletion planning/autoware_route_handler/src/route_handler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "autoware_route_handler/route_handler.hpp"
#include "autoware/route_handler/route_handler.hpp"

#include <autoware_utils/math/normalization.hpp>
#include <lanelet2_extension/utility/message_conversion.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
#include "autoware_test_utils/mock_data_parser.hpp"
#include "gtest/gtest.h"

#include <autoware_route_handler/route_handler.hpp>
#include <autoware/route_handler/route_handler.hpp>
#include <lanelet2_extension/io/autoware_osm_parser.hpp>
#include <lanelet2_extension/projection/mgrs_projector.hpp>
#include <lanelet2_extension/utility/message_conversion.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@
#else
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
#endif
#include <autoware_route_handler/route_handler.hpp>
#include <autoware/route_handler/route_handler.hpp>
#include <tier4_autoware_utils/ros/polling_subscriber.hpp>

#include <tf2_ros/buffer.h>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@
#ifndef TYPE_ALIAS_HPP_
#define TYPE_ALIAS_HPP_

#include "autoware_route_handler/route_handler.hpp"
#include "autoware/route_handler/route_handler.hpp"
#include "tier4_autoware_utils/geometry/geometry.hpp"

#include "autoware_map_msgs/msg/lanelet_map_bin.hpp"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
#ifndef UTILS_HPP_
#define UTILS_HPP_

#include "autoware_route_handler/route_handler.hpp"
#include "autoware/route_handler/route_handler.hpp"
#include "type_alias.hpp"

#include <rclcpp/time.hpp>
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 "autoware_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 "autoware_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 @@ -22,7 +22,7 @@
#include "autoware/behavior_path_planner_common/utils/utils.hpp"
#include "rclcpp/logger.hpp"

#include <autoware_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 Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
#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 <autoware/route_handler/route_handler.hpp>
#include <lanelet2_extension/regulatory_elements/Forward.hpp>
#include <lanelet2_extension/utility/utilities.hpp>
#include <rclcpp/rclcpp/clock.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,8 +23,8 @@
#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 <autoware_route_handler/route_handler.hpp>
#include <magic_enum.hpp>
#include <motion_utils/marker/marker_helper.hpp>
#include <motion_utils/trajectory/path_with_lane_id.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@

#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 <autoware/route_handler/route_handler.hpp>
#include <lanelet2_extension/utility/message_conversion.hpp>
#include <tier4_autoware_utils/geometry/boost_geometry.hpp>
#include <tier4_autoware_utils/geometry/geometry.hpp>
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 <autoware_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 <autoware_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
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 <autoware_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 Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
#ifndef AUTOWARE__BEHAVIOR_VELOCITY_PLANNER_COMMON__PLANNER_DATA_HPP_
#define AUTOWARE__BEHAVIOR_VELOCITY_PLANNER_COMMON__PLANNER_DATA_HPP_

#include "autoware_route_handler/route_handler.hpp"
#include "autoware/route_handler/route_handler.hpp"

#include <autoware/behavior_velocity_planner_common/utilization/util.hpp>
#include <autoware/velocity_smoother/smoother/smoother_base.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@

#include "types.hpp"

#include <autoware_route_handler/route_handler.hpp>
#include <autoware/route_handler/route_handler.hpp>
#include <rclcpp/logger.hpp>

#include <autoware_perception_msgs/msg/predicted_objects.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@

#include "types.hpp"

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

#include <lanelet2_core/LaneletMap.h>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
#ifndef TYPES_HPP_
#define TYPES_HPP_

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

#include <autoware_perception_msgs/msg/predicted_objects.hpp>
#include <autoware_planning_msgs/msg/trajectory.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,8 @@
#ifndef AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON__PLANNER_DATA_HPP_
#define AUTOWARE__MOTION_VELOCITY_PLANNER_COMMON__PLANNER_DATA_HPP_

#include <autoware/route_handler/route_handler.hpp>
#include <autoware/velocity_smoother/smoother/smoother_base.hpp>
#include <autoware_route_handler/route_handler.hpp>
#include <autoware_vehicle_info_utils/vehicle_info_utils.hpp>

#include <autoware_map_msgs/msg/lanelet_map_bin.hpp>
Expand Down

0 comments on commit 82a10de

Please sign in to comment.