Skip to content

Commit

Permalink
refactor(obstacle_cruise_planner)!: add autoware_ prefix (#7419)
Browse files Browse the repository at this point in the history
Signed-off-by: Yuki Takagi <yuki.takagi@tier4.jp>
  • Loading branch information
yuki-takagi-66 authored Jun 11, 2024
1 parent e3dc8bb commit 822519d
Show file tree
Hide file tree
Showing 43 changed files with 103 additions and 102 deletions.
2 changes: 1 addition & 1 deletion .github/CODEOWNERS
Original file line number Diff line number Diff line change
Expand Up @@ -190,7 +190,7 @@ planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/**
planning/motion_velocity_planner/autoware_motion_velocity_planner_common/** maxime.clement@tier4.jp
planning/motion_velocity_planner/autoware_motion_velocity_planner_node/** maxime.clement@tier4.jp
planning/autoware_objects_of_interest_marker_interface/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp zulfaqar.azmi@tier4.jp
planning/obstacle_cruise_planner/** kosuke.takeuchi@tier4.jp satoshi.ota@tier4.jp takayuki.murooka@tier4.jp yuki.takagi@tier4.jp
planning/autoware_obstacle_cruise_planner/** kosuke.takeuchi@tier4.jp satoshi.ota@tier4.jp takayuki.murooka@tier4.jp yuki.takagi@tier4.jp
planning/obstacle_stop_planner/** berkay@leodrive.ai bnk@leodrive.ai satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp
planning/obstacle_velocity_limiter/** maxime.clement@tier4.jp
planning/autoware_path_smoother/** maxime.clement@tier4.jp takayuki.murooka@tier4.jp
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -169,7 +169,7 @@
<group>
<group if="$(eval &quot;'$(var motion_stop_planner_type)' == 'obstacle_cruise_planner'&quot;)">
<load_composable_node target="/planning/scenario_planning/lane_driving/motion_planning/motion_planning_container">
<composable_node pkg="obstacle_cruise_planner" plugin="motion_planning::ObstacleCruisePlannerNode" name="obstacle_cruise_planner" namespace="">
<composable_node pkg="autoware_obstacle_cruise_planner" plugin="autoware::motion_planning::ObstacleCruisePlannerNode" name="obstacle_cruise_planner" namespace="">
<!-- topic remap -->
<remap from="~/input/trajectory" to="obstacle_velocity_limiter/trajectory"/>
<remap from="~/input/odometry" to="/localization/kinematic_state"/>
Expand Down
2 changes: 1 addition & 1 deletion launch/tier4_planning_launch/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -63,6 +63,7 @@
<exec_depend>autoware_external_velocity_limit_selector</exec_depend>
<exec_depend>autoware_freespace_planner</exec_depend>
<exec_depend>autoware_mission_planner</exec_depend>
<exec_depend>autoware_obstacle_cruise_planner</exec_depend>
<exec_depend>autoware_path_optimizer</exec_depend>
<exec_depend>autoware_planning_topic_converter</exec_depend>
<exec_depend>autoware_planning_validator</exec_depend>
Expand All @@ -72,7 +73,6 @@
<exec_depend>autoware_velocity_smoother</exec_depend>
<exec_depend>behavior_path_planner</exec_depend>
<exec_depend>glog_component</exec_depend>
<exec_depend>obstacle_cruise_planner</exec_depend>
<exec_depend>obstacle_stop_planner</exec_depend>
<exec_depend>planning_evaluator</exec_depend>

Expand Down
4 changes: 2 additions & 2 deletions planning/.pages
Original file line number Diff line number Diff line change
Expand Up @@ -47,8 +47,8 @@ nav:
- 'Model Predictive Trajectory (MPT)': planning/autoware_path_optimizer/docs/mpt
- 'How to Debug': planning/autoware_path_optimizer/docs/debug
- 'Obstacle Cruise Planner':
- 'About Obstacle Cruise': planning/obstacle_cruise_planner
- 'How to Debug': planning/obstacle_cruise_planner/docs/debug
- 'About Obstacle Cruise': planning/autoware_obstacle_cruise_planner
- 'How to Debug': planning/autoware_obstacle_cruise_planner/docs/debug
- 'Obstacle Stop Planner': planning/obstacle_stop_planner
- 'Obstacle Velocity Limiter': planning/obstacle_velocity_limiter
- 'Path Smoother':
Expand Down
Original file line number Diff line number Diff line change
@@ -1,12 +1,12 @@
cmake_minimum_required(VERSION 3.14)
project(obstacle_cruise_planner)
project(autoware_obstacle_cruise_planner)

find_package(autoware_cmake REQUIRED)
autoware_package()

find_package(Eigen3 REQUIRED)

ament_auto_add_library(obstacle_cruise_planner_core SHARED
ament_auto_add_library(autoware_obstacle_cruise_planner_core SHARED
src/node.cpp
src/utils.cpp
src/polygon_utils.cpp
Expand All @@ -16,19 +16,19 @@ ament_auto_add_library(obstacle_cruise_planner_core SHARED
src/planner_interface.cpp
)

rclcpp_components_register_node(obstacle_cruise_planner_core
PLUGIN "motion_planning::ObstacleCruisePlannerNode"
EXECUTABLE obstacle_cruise_planner
rclcpp_components_register_node(autoware_obstacle_cruise_planner_core
PLUGIN "autoware::motion_planning::ObstacleCruisePlannerNode"
EXECUTABLE autoware_obstacle_cruise_planner
)

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
ament_add_ros_isolated_gtest(test_${PROJECT_NAME}
test/test_${PROJECT_NAME}_node_interface.cpp
test/test_obstacle_cruise_planner_node_interface.cpp
)
target_link_libraries(test_${PROJECT_NAME}
obstacle_cruise_planner_core
autoware_obstacle_cruise_planner_core
)
endif()

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

## Overview

The `obstacle_cruise_planner` package has following modules.
The `autoware_obstacle_cruise_planner` package has following modules.

- Stop planning
- stop when there is a static obstacle near the trajectory.
Expand Down Expand Up @@ -286,7 +286,7 @@ The calculated velocity is inserted in the trajectory where the obstacle is insi

### Flowchart

Successive functions consist of `obstacle_cruise_planner` as follows.
Successive functions consist of `autoware_obstacle_cruise_planner` as follows.

Various algorithms for stop and cruise planning will be implemented, and one of them is designated depending on the use cases.
The core algorithm implementation `generateTrajectory` depends on the designated algorithm.
Expand Down Expand Up @@ -380,9 +380,9 @@ under construction
### Prioritization of behavior module's stop point

When stopping for a pedestrian walking on the crosswalk, the behavior module inserts the zero velocity in the trajectory in front of the crosswalk.
Also `obstacle_cruise_planner`'s stop planning also works, and the ego may not reach the behavior module's stop point since the safe distance defined in `obstacle_cruise_planner` may be longer than the behavior module's safe distance.
To resolve this non-alignment of the stop point between the behavior module and `obstacle_cruise_planner`, `common.min_behavior_stop_margin` is defined.
In the case of the crosswalk described above, `obstacle_cruise_planner` inserts the stop point with a distance `common.min_behavior_stop_margin` at minimum between the ego and obstacle.
Also `autoware_obstacle_cruise_planner`'s stop planning also works, and the ego may not reach the behavior module's stop point since the safe distance defined in `autoware_obstacle_cruise_planner` may be longer than the behavior module's safe distance.
To resolve this non-alignment of the stop point between the behavior module and `autoware_obstacle_cruise_planner`, `common.min_behavior_stop_margin` is defined.
In the case of the crosswalk described above, `autoware_obstacle_cruise_planner` inserts the stop point with a distance `common.min_behavior_stop_margin` at minimum between the ego and obstacle.

| Parameter | Type | Description |
| --------------------------------- | ------ | ---------------------------------------------------------------------- |
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,13 +12,13 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef OBSTACLE_CRUISE_PLANNER__COMMON_STRUCTS_HPP_
#define OBSTACLE_CRUISE_PLANNER__COMMON_STRUCTS_HPP_
#ifndef AUTOWARE_OBSTACLE_CRUISE_PLANNER__COMMON_STRUCTS_HPP_
#define AUTOWARE_OBSTACLE_CRUISE_PLANNER__COMMON_STRUCTS_HPP_

#include "autoware_obstacle_cruise_planner/type_alias.hpp"
#include "motion_utils/trajectory/conversion.hpp"
#include "motion_utils/trajectory/interpolation.hpp"
#include "motion_utils/trajectory/trajectory.hpp"
#include "obstacle_cruise_planner/type_alias.hpp"
#include "tier4_autoware_utils/geometry/boost_polygon_utils.hpp"
#include "tier4_autoware_utils/ros/update_param.hpp"
#include "tier4_autoware_utils/ros/uuid_helper.hpp"
Expand Down Expand Up @@ -302,4 +302,4 @@ struct EgoNearestParam
double yaw_threshold;
};

#endif // OBSTACLE_CRUISE_PLANNER__COMMON_STRUCTS_HPP_
#endif // AUTOWARE_OBSTACLE_CRUISE_PLANNER__COMMON_STRUCTS_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,13 +12,13 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef OBSTACLE_CRUISE_PLANNER__NODE_HPP_
#define OBSTACLE_CRUISE_PLANNER__NODE_HPP_
#ifndef AUTOWARE_OBSTACLE_CRUISE_PLANNER__NODE_HPP_
#define AUTOWARE_OBSTACLE_CRUISE_PLANNER__NODE_HPP_

#include "obstacle_cruise_planner/common_structs.hpp"
#include "obstacle_cruise_planner/optimization_based_planner/optimization_based_planner.hpp"
#include "obstacle_cruise_planner/pid_based_planner/pid_based_planner.hpp"
#include "obstacle_cruise_planner/type_alias.hpp"
#include "autoware_obstacle_cruise_planner/common_structs.hpp"
#include "autoware_obstacle_cruise_planner/optimization_based_planner/optimization_based_planner.hpp"
#include "autoware_obstacle_cruise_planner/pid_based_planner/pid_based_planner.hpp"
#include "autoware_obstacle_cruise_planner/type_alias.hpp"
#include "signal_processing/lowpass_filter_1d.hpp"
#include "tier4_autoware_utils/ros/logger_level_configure.hpp"
#include "tier4_autoware_utils/ros/polling_subscriber.hpp"
Expand All @@ -36,7 +36,7 @@
#include <unordered_map>
#include <vector>

namespace motion_planning
namespace autoware::motion_planning
{
class ObstacleCruisePlannerNode : public rclcpp::Node
{
Expand Down Expand Up @@ -278,6 +278,6 @@ class ObstacleCruisePlannerNode : public rclcpp::Node

std::unique_ptr<tier4_autoware_utils::PublishedTimePublisher> published_time_publisher_;
};
} // namespace motion_planning
} // namespace autoware::motion_planning

#endif // OBSTACLE_CRUISE_PLANNER__NODE_HPP_
#endif // AUTOWARE_OBSTACLE_CRUISE_PLANNER__NODE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,14 +12,14 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__OPTIMIZATION_BASED_PLANNER_HPP_
#define OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__OPTIMIZATION_BASED_PLANNER_HPP_
#ifndef AUTOWARE_OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__OPTIMIZATION_BASED_PLANNER_HPP_ // NOLINT
#define AUTOWARE_OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__OPTIMIZATION_BASED_PLANNER_HPP_ // NOLINT

#include "autoware_obstacle_cruise_planner/optimization_based_planner/s_boundary.hpp"
#include "autoware_obstacle_cruise_planner/optimization_based_planner/velocity_optimizer.hpp"
#include "autoware_obstacle_cruise_planner/planner_interface.hpp"
#include "autoware_obstacle_cruise_planner/type_alias.hpp"
#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp"
#include "obstacle_cruise_planner/optimization_based_planner/s_boundary.hpp"
#include "obstacle_cruise_planner/optimization_based_planner/velocity_optimizer.hpp"
#include "obstacle_cruise_planner/planner_interface.hpp"
#include "obstacle_cruise_planner/type_alias.hpp"

#include <lanelet2_extension/utility/message_conversion.hpp>
#include <lanelet2_extension/utility/utilities.hpp>
Expand Down Expand Up @@ -117,5 +117,6 @@ class OptimizationBasedPlanner : public PlannerInterface
double engage_exit_ratio_;
double stop_dist_to_prohibit_engage_;
};

#endif // OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__OPTIMIZATION_BASED_PLANNER_HPP_
// clang-format off
#endif // AUTOWARE_OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__OPTIMIZATION_BASED_PLANNER_HPP_ // NOLINT
// clang-format on
Original file line number Diff line number Diff line change
Expand Up @@ -11,8 +11,8 @@
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__S_BOUNDARY_HPP_
#define OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__S_BOUNDARY_HPP_
#ifndef AUTOWARE_OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__S_BOUNDARY_HPP_
#define AUTOWARE_OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__S_BOUNDARY_HPP_

#include <limits>
#include <vector>
Expand All @@ -30,4 +30,4 @@ class SBoundary

using SBoundaries = std::vector<SBoundary>;

#endif // OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__S_BOUNDARY_HPP_
#endif // AUTOWARE_OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__S_BOUNDARY_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -11,10 +11,10 @@
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__VELOCITY_OPTIMIZER_HPP_
#define OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__VELOCITY_OPTIMIZER_HPP_
#ifndef AUTOWARE_OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__VELOCITY_OPTIMIZER_HPP_
#define AUTOWARE_OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__VELOCITY_OPTIMIZER_HPP_

#include "obstacle_cruise_planner/optimization_based_planner/s_boundary.hpp"
#include "autoware_obstacle_cruise_planner/optimization_based_planner/s_boundary.hpp"
#include "osqp_interface/osqp_interface.hpp"

#include <vector>
Expand Down Expand Up @@ -72,4 +72,4 @@ class VelocityOptimizer
autoware::common::osqp::OSQPInterface qp_solver_;
};

#endif // OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__VELOCITY_OPTIMIZER_HPP_
#endif // AUTOWARE_OBSTACLE_CRUISE_PLANNER__OPTIMIZATION_BASED_PLANNER__VELOCITY_OPTIMIZER_HPP_
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 OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__CRUISE_PLANNING_DEBUG_INFO_HPP_
#define OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__CRUISE_PLANNING_DEBUG_INFO_HPP_
#ifndef AUTOWARE_OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__CRUISE_PLANNING_DEBUG_INFO_HPP_
#define AUTOWARE_OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__CRUISE_PLANNING_DEBUG_INFO_HPP_

#include <rclcpp/rclcpp.hpp>

Expand Down Expand Up @@ -94,4 +94,4 @@ class CruisePlanningDebugInfo
std::array<double, static_cast<int>(TYPE::SIZE)> info_;
};

#endif // OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__CRUISE_PLANNING_DEBUG_INFO_HPP_
#endif // AUTOWARE_OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__CRUISE_PLANNING_DEBUG_INFO_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,12 +12,12 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__PID_BASED_PLANNER_HPP_
#define OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__PID_BASED_PLANNER_HPP_
#ifndef AUTOWARE_OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__PID_BASED_PLANNER_HPP_
#define AUTOWARE_OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__PID_BASED_PLANNER_HPP_

#include "obstacle_cruise_planner/pid_based_planner/cruise_planning_debug_info.hpp"
#include "obstacle_cruise_planner/pid_based_planner/pid_controller.hpp"
#include "obstacle_cruise_planner/planner_interface.hpp"
#include "autoware_obstacle_cruise_planner/pid_based_planner/cruise_planning_debug_info.hpp"
#include "autoware_obstacle_cruise_planner/pid_based_planner/pid_controller.hpp"
#include "autoware_obstacle_cruise_planner/planner_interface.hpp"
#include "signal_processing/lowpass_filter_1d.hpp"

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

#endif // OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__PID_BASED_PLANNER_HPP_
#endif // AUTOWARE_OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__PID_BASED_PLANNER_HPP_
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 OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__PID_CONTROLLER_HPP_
#define OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__PID_CONTROLLER_HPP_
#ifndef AUTOWARE_OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__PID_CONTROLLER_HPP_
#define AUTOWARE_OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__PID_CONTROLLER_HPP_

#include <optional>

Expand Down Expand Up @@ -59,4 +59,4 @@ class PIDController
std::optional<double> prev_error_;
};

#endif // OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__PID_CONTROLLER_HPP_
#endif // AUTOWARE_OBSTACLE_CRUISE_PLANNER__PID_BASED_PLANNER__PID_CONTROLLER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,14 +12,14 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef OBSTACLE_CRUISE_PLANNER__PLANNER_INTERFACE_HPP_
#define OBSTACLE_CRUISE_PLANNER__PLANNER_INTERFACE_HPP_
#ifndef AUTOWARE_OBSTACLE_CRUISE_PLANNER__PLANNER_INTERFACE_HPP_
#define AUTOWARE_OBSTACLE_CRUISE_PLANNER__PLANNER_INTERFACE_HPP_

#include "autoware_obstacle_cruise_planner/common_structs.hpp"
#include "autoware_obstacle_cruise_planner/stop_planning_debug_info.hpp"
#include "autoware_obstacle_cruise_planner/type_alias.hpp"
#include "autoware_obstacle_cruise_planner/utils.hpp"
#include "motion_utils/trajectory/trajectory.hpp"
#include "obstacle_cruise_planner/common_structs.hpp"
#include "obstacle_cruise_planner/stop_planning_debug_info.hpp"
#include "obstacle_cruise_planner/type_alias.hpp"
#include "obstacle_cruise_planner/utils.hpp"
#include "tier4_autoware_utils/ros/update_param.hpp"
#include "tier4_autoware_utils/system/stop_watch.hpp"

Expand Down Expand Up @@ -425,4 +425,4 @@ class PlannerInterface
std::nullopt};
};

#endif // OBSTACLE_CRUISE_PLANNER__PLANNER_INTERFACE_HPP_
#endif // AUTOWARE_OBSTACLE_CRUISE_PLANNER__PLANNER_INTERFACE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,12 +12,12 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef OBSTACLE_CRUISE_PLANNER__POLYGON_UTILS_HPP_
#define OBSTACLE_CRUISE_PLANNER__POLYGON_UTILS_HPP_
#ifndef AUTOWARE_OBSTACLE_CRUISE_PLANNER__POLYGON_UTILS_HPP_
#define AUTOWARE_OBSTACLE_CRUISE_PLANNER__POLYGON_UTILS_HPP_

#include "autoware_obstacle_cruise_planner/common_structs.hpp"
#include "autoware_obstacle_cruise_planner/type_alias.hpp"
#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp"
#include "obstacle_cruise_planner/common_structs.hpp"
#include "obstacle_cruise_planner/type_alias.hpp"
#include "tier4_autoware_utils/geometry/boost_geometry.hpp"

#include <boost/geometry.hpp>
Expand Down Expand Up @@ -52,4 +52,4 @@ std::vector<PointWithStamp> getCollisionPoints(

} // namespace polygon_utils

#endif // OBSTACLE_CRUISE_PLANNER__POLYGON_UTILS_HPP_
#endif // AUTOWARE_OBSTACLE_CRUISE_PLANNER__POLYGON_UTILS_HPP_
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 OBSTACLE_CRUISE_PLANNER__STOP_PLANNING_DEBUG_INFO_HPP_
#define OBSTACLE_CRUISE_PLANNER__STOP_PLANNING_DEBUG_INFO_HPP_
#ifndef AUTOWARE_OBSTACLE_CRUISE_PLANNER__STOP_PLANNING_DEBUG_INFO_HPP_
#define AUTOWARE_OBSTACLE_CRUISE_PLANNER__STOP_PLANNING_DEBUG_INFO_HPP_

#include <rclcpp/rclcpp.hpp>

Expand Down Expand Up @@ -85,4 +85,4 @@ class StopPlanningDebugInfo
std::array<double, static_cast<int>(TYPE::SIZE)> info_;
};

#endif // OBSTACLE_CRUISE_PLANNER__STOP_PLANNING_DEBUG_INFO_HPP_
#endif // AUTOWARE_OBSTACLE_CRUISE_PLANNER__STOP_PLANNING_DEBUG_INFO_HPP_
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 OBSTACLE_CRUISE_PLANNER__TYPE_ALIAS_HPP_
#define OBSTACLE_CRUISE_PLANNER__TYPE_ALIAS_HPP_
#ifndef AUTOWARE_OBSTACLE_CRUISE_PLANNER__TYPE_ALIAS_HPP_
#define AUTOWARE_OBSTACLE_CRUISE_PLANNER__TYPE_ALIAS_HPP_

#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp"

Expand Down Expand Up @@ -63,4 +63,4 @@ namespace bg = boost::geometry;
using tier4_autoware_utils::Point2d;
using tier4_autoware_utils::Polygon2d;

#endif // OBSTACLE_CRUISE_PLANNER__TYPE_ALIAS_HPP_
#endif // AUTOWARE_OBSTACLE_CRUISE_PLANNER__TYPE_ALIAS_HPP_
Loading

0 comments on commit 822519d

Please sign in to comment.