|
12 | 12 | // See the License for the specific language governing permissions and
|
13 | 13 | // limitations under the License.
|
14 | 14 |
|
15 |
| -#ifndef STATIC_CENTERLINE_GENERATOR__CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ |
16 |
| -STATIC_CENTERLINE_GENERATOR__CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT |
17 |
| -#define STATIC_CENTERLINE_GENERATOR__CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ |
18 |
| - STATIC_CENTERLINE_GENERATOR__CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT |
| 15 | +#ifndef STATIC_CENTERLINE_GENERATOR__CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT |
| 16 | +#define STATIC_CENTERLINE_GENERATOR__CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT |
19 | 17 |
|
20 | 18 | #include "rclcpp/rclcpp.hpp"
|
21 |
| -#include "route_handler/route_handler.hpp" |
22 | 19 | #include "static_centerline_generator/type_alias.hpp"
|
23 | 20 |
|
24 |
| -#include "autoware_auto_planning_msgs/msg/path.hpp" |
25 |
| -#include "autoware_auto_planning_msgs/msg/path_with_lane_id.hpp" |
26 |
| -#include "autoware_auto_planning_msgs/msg/trajectory_point.hpp" |
27 |
| - |
28 | 21 | #include <vector>
|
29 | 22 |
|
30 |
| - namespace autoware::static_centerline_generator |
| 23 | +namespace static_centerline_generator |
| 24 | +{ |
| 25 | +class OptimizationTrajectoryBasedCenterline |
31 | 26 | {
|
32 |
| - using ::autoware_auto_planning_msgs::msg::Path; |
33 |
| - using ::autoware_auto_planning_msgs::msg::PathWithLaneId; |
34 |
| - using ::autoware_auto_planning_msgs::msg::TrajectoryPoint; |
35 |
| - using ::route_handler::RouteHandler; |
36 |
| - class OptimizationTrajectoryBasedCenterline |
37 |
| - { |
38 |
| - public: |
39 |
| - OptimizationTrajectoryBasedCenterline() = default; |
40 |
| - explicit OptimizationTrajectoryBasedCenterline(rclcpp::Node & node); |
41 |
| - std::vector<TrajectoryPoint> generate_centerline_with_optimization( |
42 |
| - rclcpp::Node & node, const RouteHandler & route_handler, |
43 |
| - const std::vector<lanelet::Id> & route_lane_ids); |
| 27 | +public: |
| 28 | + OptimizationTrajectoryBasedCenterline() = default; |
| 29 | + explicit OptimizationTrajectoryBasedCenterline(rclcpp::Node & node); |
| 30 | + std::vector<TrajectoryPoint> generate_centerline_with_optimization( |
| 31 | + rclcpp::Node & node, const RouteHandler & route_handler, |
| 32 | + const std::vector<lanelet::Id> & route_lane_ids); |
44 | 33 |
|
45 |
| - private: |
46 |
| - [[nodiscard]] static std::vector<TrajectoryPoint> optimize_trajectory(const Path & raw_path); |
| 34 | +private: |
| 35 | + std::vector<TrajectoryPoint> optimize_trajectory(const Path & raw_path) const; |
47 | 36 |
|
48 |
| - rclcpp::Publisher<PathWithLaneId>::SharedPtr pub_raw_path_with_lane_id_{nullptr}; |
49 |
| - rclcpp::Publisher<Path>::SharedPtr pub_raw_path_{nullptr}; |
50 |
| - }; |
51 |
| -} // namespace autoware::static_centerline_generator |
| 37 | + rclcpp::Publisher<PathWithLaneId>::SharedPtr pub_raw_path_with_lane_id_{nullptr}; |
| 38 | + rclcpp::Publisher<Path>::SharedPtr pub_raw_path_{nullptr}; |
| 39 | +}; |
| 40 | +} // namespace static_centerline_generator |
52 | 41 | // clang-format off
|
53 | 42 | #endif // STATIC_CENTERLINE_GENERATOR__CENTERLINE_SOURCE__OPTIMIZATION_TRAJECTORY_BASED_CENTERLINE_HPP_ // NOLINT
|
54 | 43 | // clang-format on
|
0 commit comments