15
15
#ifndef PREDICTED_PATH_CHECKER__PREDICTED_PATH_CHECKER_NODE_HPP_
16
16
#define PREDICTED_PATH_CHECKER__PREDICTED_PATH_CHECKER_NODE_HPP_
17
17
18
+ #include < autoware/component_interface_specs/control.hpp>
18
19
#include < autoware/motion_utils/trajectory/conversion.hpp>
19
20
#include < autoware/motion_utils/trajectory/trajectory.hpp>
20
21
#include < autoware/universe_utils/geometry/geometry.hpp>
21
22
#include < autoware/universe_utils/ros/self_pose_listener.hpp>
22
23
#include < autoware_vehicle_info_utils/vehicle_info.hpp>
23
24
#include < autoware_vehicle_info_utils/vehicle_info_utils.hpp>
24
- #include < autoware/component_interface_specs/control.hpp>
25
25
#include < component_interface_utils/rclcpp.hpp>
26
26
#include < diagnostic_updater/diagnostic_updater.hpp>
27
27
#include < predicted_path_checker/collision_checker.hpp>
@@ -96,10 +96,12 @@ class PredictedPathCheckerNode : public rclcpp::Node
96
96
sub_predicted_trajectory_;
97
97
rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr sub_odom_;
98
98
rclcpp::Subscription<geometry_msgs::msg::AccelWithCovarianceStamped>::SharedPtr sub_accel_;
99
- component_interface_utils::Subscription<autoware::component_interface_specs::control_interface::IsStopped>::SharedPtr sub_stop_state_;
99
+ component_interface_utils::Subscription<
100
+ autoware::component_interface_specs::control_interface::IsStopped>::SharedPtr sub_stop_state_;
100
101
101
102
// Client
102
- component_interface_utils::Client<autoware::component_interface_specs::control_interface::SetStop>::SharedPtr cli_set_stop_;
103
+ component_interface_utils::Client<
104
+ autoware::component_interface_specs::control_interface::SetStop>::SharedPtr cli_set_stop_;
103
105
104
106
// Data Buffer
105
107
geometry_msgs::msg::PoseStamped::ConstSharedPtr current_pose_;
@@ -108,7 +110,8 @@ class PredictedPathCheckerNode : public rclcpp::Node
108
110
PredictedObjects::ConstSharedPtr object_ptr_{nullptr };
109
111
autoware_planning_msgs::msg::Trajectory::ConstSharedPtr reference_trajectory_;
110
112
autoware_planning_msgs::msg::Trajectory::ConstSharedPtr predicted_trajectory_;
111
- autoware::component_interface_specs::control_interface::IsStopped::Message::ConstSharedPtr is_stopped_ptr_{nullptr };
113
+ autoware::component_interface_specs::control_interface::IsStopped::Message::ConstSharedPtr
114
+ is_stopped_ptr_{nullptr };
112
115
113
116
// Core
114
117
std::unique_ptr<CollisionChecker> collision_checker_;
@@ -126,7 +129,9 @@ class PredictedPathCheckerNode : public rclcpp::Node
126
129
void onPredictedTrajectory (const autoware_planning_msgs::msg::Trajectory::SharedPtr msg);
127
130
void onOdom (const nav_msgs::msg::Odometry::SharedPtr msg);
128
131
void onAccel (const geometry_msgs::msg::AccelWithCovarianceStamped::SharedPtr msg);
129
- void onIsStopped (const autoware::component_interface_specs::control_interface::IsStopped::Message::ConstSharedPtr msg);
132
+ void onIsStopped (
133
+ const autoware::component_interface_specs::control_interface::IsStopped::Message::ConstSharedPtr
134
+ msg);
130
135
131
136
// Timer
132
137
rclcpp::TimerBase::SharedPtr timer_;
0 commit comments