|
18 | 18 | #include <autoware/motion_utils/trajectory/trajectory.hpp>
|
19 | 19 | #include <rclcpp/rclcpp.hpp>
|
20 | 20 |
|
| 21 | +#include <autoware_internal_planning_msgs/msg/control_point.hpp> |
21 | 22 | #include <autoware_internal_planning_msgs/msg/path_point_with_lane_id.hpp>
|
| 23 | +#include <autoware_internal_planning_msgs/msg/planning_factor.hpp> |
| 24 | +#include <autoware_internal_planning_msgs/msg/planning_factor_array.hpp> |
| 25 | +#include <autoware_internal_planning_msgs/msg/safety_factor_array.hpp> |
22 | 26 | #include <autoware_planning_msgs/msg/path_point.hpp>
|
23 | 27 | #include <autoware_planning_msgs/msg/trajectory_point.hpp>
|
24 | 28 | #include <geometry_msgs/msg/pose.hpp>
|
25 |
| -#include <tier4_planning_msgs/msg/control_point.hpp> |
26 |
| -#include <tier4_planning_msgs/msg/planning_factor.hpp> |
27 |
| -#include <tier4_planning_msgs/msg/planning_factor_array.hpp> |
28 |
| -#include <tier4_planning_msgs/msg/safety_factor_array.hpp> |
29 | 29 |
|
30 | 30 | #include <string>
|
31 | 31 | #include <vector>
|
32 | 32 |
|
33 | 33 | namespace autoware::planning_factor_interface
|
34 | 34 | {
|
35 | 35 |
|
| 36 | +using autoware_internal_planning_msgs::msg::ControlPoint; |
| 37 | +using autoware_internal_planning_msgs::msg::PlanningFactor; |
| 38 | +using autoware_internal_planning_msgs::msg::PlanningFactorArray; |
| 39 | +using autoware_internal_planning_msgs::msg::SafetyFactorArray; |
36 | 40 | using geometry_msgs::msg::Pose;
|
37 |
| -using tier4_planning_msgs::msg::ControlPoint; |
38 |
| -using tier4_planning_msgs::msg::PlanningFactor; |
39 |
| -using tier4_planning_msgs::msg::PlanningFactorArray; |
40 |
| -using tier4_planning_msgs::msg::SafetyFactorArray; |
41 | 41 |
|
42 | 42 | class PlanningFactorInterface
|
43 | 43 | {
|
@@ -124,13 +124,13 @@ class PlanningFactorInterface
|
124 | 124 | const SafetyFactorArray & safety_factors, const bool is_driving_forward = true,
|
125 | 125 | const double velocity = 0.0, const double shift_length = 0.0, const std::string & detail = "")
|
126 | 126 | {
|
127 |
| - const auto control_point = tier4_planning_msgs::build<ControlPoint>() |
| 127 | + const auto control_point = autoware_internal_planning_msgs::build<ControlPoint>() |
128 | 128 | .pose(control_point_pose)
|
129 | 129 | .velocity(velocity)
|
130 | 130 | .shift_length(shift_length)
|
131 | 131 | .distance(distance);
|
132 | 132 |
|
133 |
| - const auto factor = tier4_planning_msgs::build<PlanningFactor>() |
| 133 | + const auto factor = autoware_internal_planning_msgs::build<PlanningFactor>() |
134 | 134 | .module(name_)
|
135 | 135 | .is_driving_forward(is_driving_forward)
|
136 | 136 | .control_points({control_point})
|
@@ -161,19 +161,19 @@ class PlanningFactorInterface
|
161 | 161 | const bool is_driving_forward = true, const double velocity = 0.0,
|
162 | 162 | const double shift_length = 0.0, const std::string & detail = "")
|
163 | 163 | {
|
164 |
| - const auto control_start_point = tier4_planning_msgs::build<ControlPoint>() |
| 164 | + const auto control_start_point = autoware_internal_planning_msgs::build<ControlPoint>() |
165 | 165 | .pose(start_pose)
|
166 | 166 | .velocity(velocity)
|
167 | 167 | .shift_length(shift_length)
|
168 | 168 | .distance(start_distance);
|
169 | 169 |
|
170 |
| - const auto control_end_point = tier4_planning_msgs::build<ControlPoint>() |
| 170 | + const auto control_end_point = autoware_internal_planning_msgs::build<ControlPoint>() |
171 | 171 | .pose(end_pose)
|
172 | 172 | .velocity(velocity)
|
173 | 173 | .shift_length(shift_length)
|
174 | 174 | .distance(end_distance);
|
175 | 175 |
|
176 |
| - const auto factor = tier4_planning_msgs::build<PlanningFactor>() |
| 176 | + const auto factor = autoware_internal_planning_msgs::build<PlanningFactor>() |
177 | 177 | .module(name_)
|
178 | 178 | .is_driving_forward(is_driving_forward)
|
179 | 179 | .control_points({control_start_point, control_end_point})
|
|
0 commit comments