Skip to content

Commit 4dc8e1b

Browse files
takayuki5168KhalilSelyan
authored and
KhalilSelyan
committedJul 22, 2024
feat(obstacle_cruise_planner): rename to include/autoware/{package_name} (#7510)
Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
1 parent 9069d07 commit 4dc8e1b

21 files changed

+71
-71
lines changed
 

‎planning/autoware_obstacle_cruise_planner/include/autoware_obstacle_cruise_planner/common_structs.hpp ‎planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/common_structs.hpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -12,10 +12,10 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef AUTOWARE_OBSTACLE_CRUISE_PLANNER__COMMON_STRUCTS_HPP_
16-
#define AUTOWARE_OBSTACLE_CRUISE_PLANNER__COMMON_STRUCTS_HPP_
15+
#ifndef AUTOWARE__OBSTACLE_CRUISE_PLANNER__COMMON_STRUCTS_HPP_
16+
#define AUTOWARE__OBSTACLE_CRUISE_PLANNER__COMMON_STRUCTS_HPP_
1717

18-
#include "autoware_obstacle_cruise_planner/type_alias.hpp"
18+
#include "autoware/obstacle_cruise_planner/type_alias.hpp"
1919
#include "motion_utils/trajectory/conversion.hpp"
2020
#include "motion_utils/trajectory/interpolation.hpp"
2121
#include "motion_utils/trajectory/trajectory.hpp"
@@ -302,4 +302,4 @@ struct EgoNearestParam
302302
double yaw_threshold;
303303
};
304304

305-
#endif // AUTOWARE_OBSTACLE_CRUISE_PLANNER__COMMON_STRUCTS_HPP_
305+
#endif // AUTOWARE__OBSTACLE_CRUISE_PLANNER__COMMON_STRUCTS_HPP_

‎planning/autoware_obstacle_cruise_planner/include/autoware_obstacle_cruise_planner/node.hpp ‎planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/node.hpp

+7-7
Original file line numberDiff line numberDiff line change
@@ -12,13 +12,13 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef AUTOWARE_OBSTACLE_CRUISE_PLANNER__NODE_HPP_
16-
#define AUTOWARE_OBSTACLE_CRUISE_PLANNER__NODE_HPP_
15+
#ifndef AUTOWARE__OBSTACLE_CRUISE_PLANNER__NODE_HPP_
16+
#define AUTOWARE__OBSTACLE_CRUISE_PLANNER__NODE_HPP_
1717

18-
#include "autoware_obstacle_cruise_planner/common_structs.hpp"
19-
#include "autoware_obstacle_cruise_planner/optimization_based_planner/optimization_based_planner.hpp"
20-
#include "autoware_obstacle_cruise_planner/pid_based_planner/pid_based_planner.hpp"
21-
#include "autoware_obstacle_cruise_planner/type_alias.hpp"
18+
#include "autoware/obstacle_cruise_planner/common_structs.hpp"
19+
#include "autoware/obstacle_cruise_planner/optimization_based_planner/optimization_based_planner.hpp"
20+
#include "autoware/obstacle_cruise_planner/pid_based_planner/pid_based_planner.hpp"
21+
#include "autoware/obstacle_cruise_planner/type_alias.hpp"
2222
#include "signal_processing/lowpass_filter_1d.hpp"
2323
#include "tier4_autoware_utils/ros/logger_level_configure.hpp"
2424
#include "tier4_autoware_utils/ros/polling_subscriber.hpp"
@@ -280,4 +280,4 @@ class ObstacleCruisePlannerNode : public rclcpp::Node
280280
};
281281
} // namespace autoware::motion_planning
282282

283-
#endif // AUTOWARE_OBSTACLE_CRUISE_PLANNER__NODE_HPP_
283+
#endif // AUTOWARE__OBSTACLE_CRUISE_PLANNER__NODE_HPP_
Original file line numberDiff line numberDiff line change
@@ -12,13 +12,13 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef AUTOWARE_OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__OPTIMIZATION_BASED_PLANNER_HPP_ // NOLINT
16-
#define AUTOWARE_OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__OPTIMIZATION_BASED_PLANNER_HPP_ // NOLINT
15+
#ifndef AUTOWARE__OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__OPTIMIZATION_BASED_PLANNER_HPP_ // NOLINT
16+
#define AUTOWARE__OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__OPTIMIZATION_BASED_PLANNER_HPP_ // NOLINT
1717

18-
#include "autoware_obstacle_cruise_planner/optimization_based_planner/s_boundary.hpp"
19-
#include "autoware_obstacle_cruise_planner/optimization_based_planner/velocity_optimizer.hpp"
20-
#include "autoware_obstacle_cruise_planner/planner_interface.hpp"
21-
#include "autoware_obstacle_cruise_planner/type_alias.hpp"
18+
#include "autoware/obstacle_cruise_planner/optimization_based_planner/s_boundary.hpp"
19+
#include "autoware/obstacle_cruise_planner/optimization_based_planner/velocity_optimizer.hpp"
20+
#include "autoware/obstacle_cruise_planner/planner_interface.hpp"
21+
#include "autoware/obstacle_cruise_planner/type_alias.hpp"
2222
#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp"
2323

2424
#include <lanelet2_extension/utility/message_conversion.hpp>
@@ -118,5 +118,5 @@ class OptimizationBasedPlanner : public PlannerInterface
118118
double stop_dist_to_prohibit_engage_;
119119
};
120120
// clang-format off
121-
#endif // AUTOWARE_OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__OPTIMIZATION_BASED_PLANNER_HPP_ // NOLINT
121+
#endif // AUTOWARE__OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__OPTIMIZATION_BASED_PLANNER_HPP_ // NOLINT
122122
// clang-format on
+3-3
Original file line numberDiff line numberDiff line change
@@ -11,8 +11,8 @@
1111
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
14-
#ifndef AUTOWARE_OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__S_BOUNDARY_HPP_
15-
#define AUTOWARE_OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__S_BOUNDARY_HPP_
14+
#ifndef AUTOWARE__OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__S_BOUNDARY_HPP_
15+
#define AUTOWARE__OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__S_BOUNDARY_HPP_
1616

1717
#include <limits>
1818
#include <vector>
@@ -30,4 +30,4 @@ class SBoundary
3030

3131
using SBoundaries = std::vector<SBoundary>;
3232

33-
#endif // AUTOWARE_OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__S_BOUNDARY_HPP_
33+
#endif // AUTOWARE__OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__S_BOUNDARY_HPP_
+4-4
Original file line numberDiff line numberDiff line change
@@ -11,10 +11,10 @@
1111
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
14-
#ifndef AUTOWARE_OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__VELOCITY_OPTIMIZER_HPP_
15-
#define AUTOWARE_OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__VELOCITY_OPTIMIZER_HPP_
14+
#ifndef AUTOWARE__OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__VELOCITY_OPTIMIZER_HPP_
15+
#define AUTOWARE__OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__VELOCITY_OPTIMIZER_HPP_
1616

17-
#include "autoware_obstacle_cruise_planner/optimization_based_planner/s_boundary.hpp"
17+
#include "autoware/obstacle_cruise_planner/optimization_based_planner/s_boundary.hpp"
1818
#include "osqp_interface/osqp_interface.hpp"
1919

2020
#include <vector>
@@ -72,4 +72,4 @@ class VelocityOptimizer
7272
autoware::common::osqp::OSQPInterface qp_solver_;
7373
};
7474

75-
#endif // AUTOWARE_OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__VELOCITY_OPTIMIZER_HPP_
75+
#endif // AUTOWARE__OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__VELOCITY_OPTIMIZER_HPP_
+3-3
Original file line numberDiff line numberDiff line change
@@ -12,8 +12,8 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef AUTOWARE_OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__CRUISE_PLANNING_DEBUG_INFO_HPP_
16-
#define AUTOWARE_OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__CRUISE_PLANNING_DEBUG_INFO_HPP_
15+
#ifndef AUTOWARE__OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__CRUISE_PLANNING_DEBUG_INFO_HPP_
16+
#define AUTOWARE__OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__CRUISE_PLANNING_DEBUG_INFO_HPP_
1717

1818
#include <rclcpp/rclcpp.hpp>
1919

@@ -94,4 +94,4 @@ class CruisePlanningDebugInfo
9494
std::array<double, static_cast<int>(TYPE::SIZE)> info_;
9595
};
9696

97-
#endif // AUTOWARE_OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__CRUISE_PLANNING_DEBUG_INFO_HPP_
97+
#endif // AUTOWARE__OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__CRUISE_PLANNING_DEBUG_INFO_HPP_
+6-6
Original file line numberDiff line numberDiff line change
@@ -12,12 +12,12 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef AUTOWARE_OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__PID_BASED_PLANNER_HPP_
16-
#define AUTOWARE_OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__PID_BASED_PLANNER_HPP_
15+
#ifndef AUTOWARE__OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__PID_BASED_PLANNER_HPP_
16+
#define AUTOWARE__OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__PID_BASED_PLANNER_HPP_
1717

18-
#include "autoware_obstacle_cruise_planner/pid_based_planner/cruise_planning_debug_info.hpp"
19-
#include "autoware_obstacle_cruise_planner/pid_based_planner/pid_controller.hpp"
20-
#include "autoware_obstacle_cruise_planner/planner_interface.hpp"
18+
#include "autoware/obstacle_cruise_planner/pid_based_planner/cruise_planning_debug_info.hpp"
19+
#include "autoware/obstacle_cruise_planner/pid_based_planner/pid_controller.hpp"
20+
#include "autoware/obstacle_cruise_planner/planner_interface.hpp"
2121
#include "signal_processing/lowpass_filter_1d.hpp"
2222

2323
#include "visualization_msgs/msg/marker_array.hpp"
@@ -137,4 +137,4 @@ class PIDBasedPlanner : public PlannerInterface
137137
std::function<double(double)> error_func_;
138138
};
139139

140-
#endif // AUTOWARE_OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__PID_BASED_PLANNER_HPP_
140+
#endif // AUTOWARE__OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__PID_BASED_PLANNER_HPP_

‎planning/autoware_obstacle_cruise_planner/include/autoware_obstacle_cruise_planner/pid_based_planner/pid_controller.hpp ‎planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/pid_based_planner/pid_controller.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -12,8 +12,8 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef AUTOWARE_OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__PID_CONTROLLER_HPP_
16-
#define AUTOWARE_OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__PID_CONTROLLER_HPP_
15+
#ifndef AUTOWARE__OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__PID_CONTROLLER_HPP_
16+
#define AUTOWARE__OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__PID_CONTROLLER_HPP_
1717

1818
#include <optional>
1919

@@ -59,4 +59,4 @@ class PIDController
5959
std::optional<double> prev_error_;
6060
};
6161

62-
#endif // AUTOWARE_OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__PID_CONTROLLER_HPP_
62+
#endif // AUTOWARE__OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__PID_CONTROLLER_HPP_

‎planning/autoware_obstacle_cruise_planner/include/autoware_obstacle_cruise_planner/planner_interface.hpp ‎planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/planner_interface.hpp

+7-7
Original file line numberDiff line numberDiff line change
@@ -12,13 +12,13 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef AUTOWARE_OBSTACLE_CRUISE_PLANNER__PLANNER_INTERFACE_HPP_
16-
#define AUTOWARE_OBSTACLE_CRUISE_PLANNER__PLANNER_INTERFACE_HPP_
15+
#ifndef AUTOWARE__OBSTACLE_CRUISE_PLANNER__PLANNER_INTERFACE_HPP_
16+
#define AUTOWARE__OBSTACLE_CRUISE_PLANNER__PLANNER_INTERFACE_HPP_
1717

18-
#include "autoware_obstacle_cruise_planner/common_structs.hpp"
19-
#include "autoware_obstacle_cruise_planner/stop_planning_debug_info.hpp"
20-
#include "autoware_obstacle_cruise_planner/type_alias.hpp"
21-
#include "autoware_obstacle_cruise_planner/utils.hpp"
18+
#include "autoware/obstacle_cruise_planner/common_structs.hpp"
19+
#include "autoware/obstacle_cruise_planner/stop_planning_debug_info.hpp"
20+
#include "autoware/obstacle_cruise_planner/type_alias.hpp"
21+
#include "autoware/obstacle_cruise_planner/utils.hpp"
2222
#include "motion_utils/trajectory/trajectory.hpp"
2323
#include "tier4_autoware_utils/ros/update_param.hpp"
2424
#include "tier4_autoware_utils/system/stop_watch.hpp"
@@ -425,4 +425,4 @@ class PlannerInterface
425425
std::nullopt};
426426
};
427427

428-
#endif // AUTOWARE_OBSTACLE_CRUISE_PLANNER__PLANNER_INTERFACE_HPP_
428+
#endif // AUTOWARE__OBSTACLE_CRUISE_PLANNER__PLANNER_INTERFACE_HPP_

‎planning/autoware_obstacle_cruise_planner/include/autoware_obstacle_cruise_planner/polygon_utils.hpp ‎planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/polygon_utils.hpp

+5-5
Original file line numberDiff line numberDiff line change
@@ -12,11 +12,11 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef AUTOWARE_OBSTACLE_CRUISE_PLANNER__POLYGON_UTILS_HPP_
16-
#define AUTOWARE_OBSTACLE_CRUISE_PLANNER__POLYGON_UTILS_HPP_
15+
#ifndef AUTOWARE__OBSTACLE_CRUISE_PLANNER__POLYGON_UTILS_HPP_
16+
#define AUTOWARE__OBSTACLE_CRUISE_PLANNER__POLYGON_UTILS_HPP_
1717

18-
#include "autoware_obstacle_cruise_planner/common_structs.hpp"
19-
#include "autoware_obstacle_cruise_planner/type_alias.hpp"
18+
#include "autoware/obstacle_cruise_planner/common_structs.hpp"
19+
#include "autoware/obstacle_cruise_planner/type_alias.hpp"
2020
#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp"
2121
#include "tier4_autoware_utils/geometry/boost_geometry.hpp"
2222

@@ -52,4 +52,4 @@ std::vector<PointWithStamp> getCollisionPoints(
5252

5353
} // namespace polygon_utils
5454

55-
#endif // AUTOWARE_OBSTACLE_CRUISE_PLANNER__POLYGON_UTILS_HPP_
55+
#endif // AUTOWARE__OBSTACLE_CRUISE_PLANNER__POLYGON_UTILS_HPP_

‎planning/autoware_obstacle_cruise_planner/include/autoware_obstacle_cruise_planner/stop_planning_debug_info.hpp ‎planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/stop_planning_debug_info.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -12,8 +12,8 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef AUTOWARE_OBSTACLE_CRUISE_PLANNER__STOP_PLANNING_DEBUG_INFO_HPP_
16-
#define AUTOWARE_OBSTACLE_CRUISE_PLANNER__STOP_PLANNING_DEBUG_INFO_HPP_
15+
#ifndef AUTOWARE__OBSTACLE_CRUISE_PLANNER__STOP_PLANNING_DEBUG_INFO_HPP_
16+
#define AUTOWARE__OBSTACLE_CRUISE_PLANNER__STOP_PLANNING_DEBUG_INFO_HPP_
1717

1818
#include <rclcpp/rclcpp.hpp>
1919

@@ -85,4 +85,4 @@ class StopPlanningDebugInfo
8585
std::array<double, static_cast<int>(TYPE::SIZE)> info_;
8686
};
8787

88-
#endif // AUTOWARE_OBSTACLE_CRUISE_PLANNER__STOP_PLANNING_DEBUG_INFO_HPP_
88+
#endif // AUTOWARE__OBSTACLE_CRUISE_PLANNER__STOP_PLANNING_DEBUG_INFO_HPP_

‎planning/autoware_obstacle_cruise_planner/include/autoware_obstacle_cruise_planner/type_alias.hpp ‎planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/type_alias.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -12,8 +12,8 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef AUTOWARE_OBSTACLE_CRUISE_PLANNER__TYPE_ALIAS_HPP_
16-
#define AUTOWARE_OBSTACLE_CRUISE_PLANNER__TYPE_ALIAS_HPP_
15+
#ifndef AUTOWARE__OBSTACLE_CRUISE_PLANNER__TYPE_ALIAS_HPP_
16+
#define AUTOWARE__OBSTACLE_CRUISE_PLANNER__TYPE_ALIAS_HPP_
1717

1818
#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp"
1919

@@ -63,4 +63,4 @@ namespace bg = boost::geometry;
6363
using tier4_autoware_utils::Point2d;
6464
using tier4_autoware_utils::Polygon2d;
6565

66-
#endif // AUTOWARE_OBSTACLE_CRUISE_PLANNER__TYPE_ALIAS_HPP_
66+
#endif // AUTOWARE__OBSTACLE_CRUISE_PLANNER__TYPE_ALIAS_HPP_

‎planning/autoware_obstacle_cruise_planner/include/autoware_obstacle_cruise_planner/utils.hpp ‎planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/utils.hpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -12,10 +12,10 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef AUTOWARE_OBSTACLE_CRUISE_PLANNER__UTILS_HPP_
16-
#define AUTOWARE_OBSTACLE_CRUISE_PLANNER__UTILS_HPP_
15+
#ifndef AUTOWARE__OBSTACLE_CRUISE_PLANNER__UTILS_HPP_
16+
#define AUTOWARE__OBSTACLE_CRUISE_PLANNER__UTILS_HPP_
1717

18-
#include "autoware_obstacle_cruise_planner/type_alias.hpp"
18+
#include "autoware/obstacle_cruise_planner/type_alias.hpp"
1919
#include "common_structs.hpp"
2020
#include "tier4_autoware_utils/geometry/geometry.hpp"
2121

@@ -95,4 +95,4 @@ size_t getIndexWithLongitudinalOffset(
9595
}
9696
} // namespace obstacle_cruise_utils
9797

98-
#endif // AUTOWARE_OBSTACLE_CRUISE_PLANNER__UTILS_HPP_
98+
#endif // AUTOWARE__OBSTACLE_CRUISE_PLANNER__UTILS_HPP_

‎planning/autoware_obstacle_cruise_planner/src/node.cpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -12,10 +12,10 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#include "autoware_obstacle_cruise_planner/node.hpp"
15+
#include "autoware/obstacle_cruise_planner/node.hpp"
1616

17-
#include "autoware_obstacle_cruise_planner/polygon_utils.hpp"
18-
#include "autoware_obstacle_cruise_planner/utils.hpp"
17+
#include "autoware/obstacle_cruise_planner/polygon_utils.hpp"
18+
#include "autoware/obstacle_cruise_planner/utils.hpp"
1919
#include "motion_utils/resample/resample.hpp"
2020
#include "motion_utils/trajectory/conversion.hpp"
2121
#include "object_recognition_utils/predicted_path_utils.hpp"

‎planning/autoware_obstacle_cruise_planner/src/optimization_based_planner/optimization_based_planner.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -12,9 +12,9 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#include "autoware_obstacle_cruise_planner/optimization_based_planner/optimization_based_planner.hpp"
15+
#include "autoware/obstacle_cruise_planner/optimization_based_planner/optimization_based_planner.hpp"
1616

17-
#include "autoware_obstacle_cruise_planner/utils.hpp"
17+
#include "autoware/obstacle_cruise_planner/utils.hpp"
1818
#include "interpolation/linear_interpolation.hpp"
1919
#include "interpolation/spline_interpolation.hpp"
2020
#include "interpolation/zero_order_hold.hpp"

‎planning/autoware_obstacle_cruise_planner/src/optimization_based_planner/velocity_optimizer.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,7 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#include "autoware_obstacle_cruise_planner/optimization_based_planner/velocity_optimizer.hpp"
15+
#include "autoware/obstacle_cruise_planner/optimization_based_planner/velocity_optimizer.hpp"
1616

1717
#include <Eigen/Core>
1818

‎planning/autoware_obstacle_cruise_planner/src/pid_based_planner/pid_based_planner.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -12,9 +12,9 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#include "autoware_obstacle_cruise_planner/pid_based_planner/pid_based_planner.hpp"
15+
#include "autoware/obstacle_cruise_planner/pid_based_planner/pid_based_planner.hpp"
1616

17-
#include "autoware_obstacle_cruise_planner/utils.hpp"
17+
#include "autoware/obstacle_cruise_planner/utils.hpp"
1818
#include "interpolation/spline_interpolation.hpp"
1919
#include "motion_utils/marker/marker_helper.hpp"
2020
#include "tier4_autoware_utils/geometry/geometry.hpp"

‎planning/autoware_obstacle_cruise_planner/src/planner_interface.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,7 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#include "autoware_obstacle_cruise_planner/planner_interface.hpp"
15+
#include "autoware/obstacle_cruise_planner/planner_interface.hpp"
1616

1717
#include "motion_utils/distance/distance.hpp"
1818
#include "motion_utils/marker/marker_helper.hpp"

‎planning/autoware_obstacle_cruise_planner/src/polygon_utils.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,7 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#include "autoware_obstacle_cruise_planner/polygon_utils.hpp"
15+
#include "autoware/obstacle_cruise_planner/polygon_utils.hpp"
1616

1717
#include "motion_utils/trajectory/trajectory.hpp"
1818
#include "tier4_autoware_utils/geometry/boost_polygon_utils.hpp"

‎planning/autoware_obstacle_cruise_planner/src/utils.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,7 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#include "autoware_obstacle_cruise_planner/utils.hpp"
15+
#include "autoware/obstacle_cruise_planner/utils.hpp"
1616

1717
#include "object_recognition_utils/predicted_path_utils.hpp"
1818
#include "tier4_autoware_utils/ros/marker_helper.hpp"

‎planning/autoware_obstacle_cruise_planner/test/test_obstacle_cruise_planner_node_interface.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,7 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#include "autoware_obstacle_cruise_planner/node.hpp"
15+
#include "autoware/obstacle_cruise_planner/node.hpp"
1616

1717
#include <ament_index_cpp/get_package_share_directory.hpp>
1818
#include <autoware_planning_test_manager/autoware_planning_test_manager.hpp>

0 commit comments

Comments
 (0)
Please sign in to comment.