Skip to content

Commit 92da629

Browse files
feat(Autoware_planning_factor_interface): replace tier4_msgs with autoware_internal_msgs (#10204)
Signed-off-by: liuXinGangChina <lxg19892021@gmail.com>
1 parent 3b0f98e commit 92da629

File tree

49 files changed

+170
-142
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

49 files changed

+170
-142
lines changed

planning/autoware_obstacle_cruise_planner/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@
1919
<buildtool_depend>autoware_cmake</buildtool_depend>
2020

2121
<depend>autoware_internal_debug_msgs</depend>
22+
<depend>autoware_internal_planning_msgs</depend>
2223
<depend>autoware_interpolation</depend>
2324
<depend>autoware_lanelet2_extension</depend>
2425
<depend>autoware_motion_utils</depend>

planning/autoware_obstacle_cruise_planner/src/pid_based_planner/pid_based_planner.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -336,8 +336,8 @@ std::vector<TrajectoryPoint> PIDBasedPlanner::planCruise(
336336

337337
planning_factor_interface_->add(
338338
stop_traj_points, planner_data.ego_pose, stop_traj_points.at(wall_idx).pose,
339-
tier4_planning_msgs::msg::PlanningFactor::NONE,
340-
tier4_planning_msgs::msg::SafetyFactorArray{});
339+
autoware_internal_planning_msgs::msg::PlanningFactor::NONE,
340+
autoware_internal_planning_msgs::msg::SafetyFactorArray{});
341341
}
342342

343343
// do cruise planning

planning/autoware_obstacle_cruise_planner/src/planner_interface.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -336,8 +336,8 @@ std::vector<TrajectoryPoint> PlannerInterface::generateStopTrajectory(
336336
const auto stop_pose = output_traj_points.at(*zero_vel_idx).pose;
337337
planning_factor_interface_->add(
338338
output_traj_points, planner_data.ego_pose, stop_pose,
339-
tier4_planning_msgs::msg::PlanningFactor::STOP,
340-
tier4_planning_msgs::msg::SafetyFactorArray{});
339+
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
340+
autoware_internal_planning_msgs::msg::SafetyFactorArray{});
341341
// Store stop reason debug data
342342
debug_data_ptr_->stop_metrics =
343343
makeMetrics("PlannerInterface", "stop", planner_data, stop_pose, *determined_stop_obstacle);
@@ -594,8 +594,8 @@ std::vector<TrajectoryPoint> PlannerInterface::generateSlowDownTrajectory(
594594
slow_down_traj_points, planner_data.ego_pose,
595595
slow_down_traj_points.at(*slow_down_start_idx).pose,
596596
slow_down_traj_points.at(*slow_down_end_idx).pose,
597-
tier4_planning_msgs::msg::PlanningFactor::SLOW_DOWN,
598-
tier4_planning_msgs::msg::SafetyFactorArray{}, planner_data.is_driving_forward,
597+
autoware_internal_planning_msgs::msg::PlanningFactor::SLOW_DOWN,
598+
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, planner_data.is_driving_forward,
599599
stable_slow_down_vel);
600600
}
601601

planning/autoware_obstacle_stop_planner/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,7 @@
2222

2323
<depend>autoware_adapi_v1_msgs</depend>
2424
<depend>autoware_internal_debug_msgs</depend>
25+
<depend>autoware_internal_planning_msgs</depend>
2526
<depend>autoware_motion_utils</depend>
2627
<depend>autoware_perception_msgs</depend>
2728
<depend>autoware_planning_factor_interface</depend>

planning/autoware_obstacle_stop_planner/src/debug_marker.cpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -194,8 +194,9 @@ void ObstacleStopPlannerDebugNode::publish()
194194
if (stop_pose_ptr_) {
195195
planning_factor_interface_->add(
196196
std::numeric_limits<float>::quiet_NaN(), *stop_pose_ptr_,
197-
tier4_planning_msgs::msg::PlanningFactor::STOP, tier4_planning_msgs::msg::SafetyFactorArray{},
198-
true /*is_driving_forward*/, 0.0, 0.0 /*shift distance*/, "");
197+
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
198+
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0,
199+
0.0 /*shift distance*/, "");
199200
}
200201
planning_factor_interface_->publish();
201202

planning/autoware_planning_factor_interface/include/autoware/planning_factor_interface/planning_factor_interface.hpp

+13-13
Original file line numberDiff line numberDiff line change
@@ -18,26 +18,26 @@
1818
#include <autoware/motion_utils/trajectory/trajectory.hpp>
1919
#include <rclcpp/rclcpp.hpp>
2020

21+
#include <autoware_internal_planning_msgs/msg/control_point.hpp>
2122
#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>
2226
#include <autoware_planning_msgs/msg/path_point.hpp>
2327
#include <autoware_planning_msgs/msg/trajectory_point.hpp>
2428
#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>
2929

3030
#include <string>
3131
#include <vector>
3232

3333
namespace autoware::planning_factor_interface
3434
{
3535

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;
3640
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;
4141

4242
class PlanningFactorInterface
4343
{
@@ -124,13 +124,13 @@ class PlanningFactorInterface
124124
const SafetyFactorArray & safety_factors, const bool is_driving_forward = true,
125125
const double velocity = 0.0, const double shift_length = 0.0, const std::string & detail = "")
126126
{
127-
const auto control_point = tier4_planning_msgs::build<ControlPoint>()
127+
const auto control_point = autoware_internal_planning_msgs::build<ControlPoint>()
128128
.pose(control_point_pose)
129129
.velocity(velocity)
130130
.shift_length(shift_length)
131131
.distance(distance);
132132

133-
const auto factor = tier4_planning_msgs::build<PlanningFactor>()
133+
const auto factor = autoware_internal_planning_msgs::build<PlanningFactor>()
134134
.module(name_)
135135
.is_driving_forward(is_driving_forward)
136136
.control_points({control_point})
@@ -161,19 +161,19 @@ class PlanningFactorInterface
161161
const bool is_driving_forward = true, const double velocity = 0.0,
162162
const double shift_length = 0.0, const std::string & detail = "")
163163
{
164-
const auto control_start_point = tier4_planning_msgs::build<ControlPoint>()
164+
const auto control_start_point = autoware_internal_planning_msgs::build<ControlPoint>()
165165
.pose(start_pose)
166166
.velocity(velocity)
167167
.shift_length(shift_length)
168168
.distance(start_distance);
169169

170-
const auto control_end_point = tier4_planning_msgs::build<ControlPoint>()
170+
const auto control_end_point = autoware_internal_planning_msgs::build<ControlPoint>()
171171
.pose(end_pose)
172172
.velocity(velocity)
173173
.shift_length(shift_length)
174174
.distance(end_distance);
175175

176-
const auto factor = tier4_planning_msgs::build<PlanningFactor>()
176+
const auto factor = autoware_internal_planning_msgs::build<PlanningFactor>()
177177
.module(name_)
178178
.is_driving_forward(is_driving_forward)
179179
.control_points({control_start_point, control_end_point})

planning/autoware_planning_factor_interface/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -13,11 +13,11 @@
1313
<buildtool_depend>ament_cmake_auto</buildtool_depend>
1414
<buildtool_depend>autoware_cmake</buildtool_depend>
1515

16+
<depend>autoware_internal_planning_msgs</depend>
1617
<depend>autoware_motion_utils</depend>
1718
<depend>autoware_planning_msgs</depend>
1819
<depend>autoware_utils</depend>
1920
<depend>rclcpp</depend>
20-
<depend>tier4_planning_msgs</depend>
2121

2222
<test_depend>ament_cmake_ros</test_depend>
2323
<test_depend>ament_lint_auto</test_depend>

planning/autoware_surround_obstacle_checker/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,7 @@
1414
<buildtool_depend>autoware_cmake</buildtool_depend>
1515
<buildtool_depend>eigen3_cmake_module</buildtool_depend>
1616

17+
<depend>autoware_internal_planning_msgs</depend>
1718
<depend>autoware_motion_utils</depend>
1819
<depend>autoware_perception_msgs</depend>
1920
<depend>autoware_planning_factor_interface</depend>

planning/autoware_surround_obstacle_checker/src/debug_marker.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -146,8 +146,8 @@ void SurroundObstacleCheckerDebugNode::publish()
146146
/* publish stop reason for autoware api */
147147
if (stop_pose_ptr_ != nullptr) {
148148
planning_factor_interface_->add(
149-
0.0, *stop_pose_ptr_, tier4_planning_msgs::msg::PlanningFactor::STOP,
150-
tier4_planning_msgs::msg::SafetyFactorArray{});
149+
0.0, *stop_pose_ptr_, autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
150+
autoware_internal_planning_msgs::msg::SafetyFactorArray{});
151151
}
152152
planning_factor_interface_->publish();
153153

planning/autoware_surround_obstacle_checker/src/debug_marker.hpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -19,9 +19,9 @@
1919
#include <autoware_vehicle_info_utils/vehicle_info_utils.hpp>
2020
#include <rclcpp/rclcpp.hpp>
2121

22+
#include <autoware_internal_planning_msgs/msg/planning_factor_array.hpp>
2223
#include <geometry_msgs/msg/polygon_stamped.hpp>
2324
#include <geometry_msgs/msg/pose.hpp>
24-
#include <tier4_planning_msgs/msg/planning_factor_array.hpp>
2525
#include <visualization_msgs/msg/marker.hpp>
2626
#include <visualization_msgs/msg/marker_array.hpp>
2727

@@ -34,10 +34,10 @@ namespace autoware::surround_obstacle_checker
3434
{
3535

3636
using autoware::vehicle_info_utils::VehicleInfo;
37+
using autoware_internal_planning_msgs::msg::ControlPoint;
38+
using autoware_internal_planning_msgs::msg::PlanningFactor;
39+
using autoware_internal_planning_msgs::msg::PlanningFactorArray;
3740
using geometry_msgs::msg::PolygonStamped;
38-
using tier4_planning_msgs::msg::ControlPoint;
39-
using tier4_planning_msgs::msg::PlanningFactor;
40-
using tier4_planning_msgs::msg::PlanningFactorArray;
4141
using visualization_msgs::msg::Marker;
4242
using visualization_msgs::msg::MarkerArray;
4343

planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/interface/scene_module_interface.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -57,11 +57,11 @@ using autoware::objects_of_interest_marker_interface::ObjectsOfInterestMarkerInt
5757
using autoware::planning_factor_interface::PlanningFactorInterface;
5858
using autoware::rtc_interface::RTCInterface;
5959
using autoware_internal_planning_msgs::msg::PathWithLaneId;
60+
using autoware_internal_planning_msgs::msg::PlanningFactor;
61+
using autoware_internal_planning_msgs::msg::SafetyFactorArray;
6062
using autoware_utils::calc_offset_pose;
6163
using autoware_utils::generate_uuid;
6264
using tier4_planning_msgs::msg::AvoidanceDebugMsgArray;
63-
using tier4_planning_msgs::msg::PlanningFactor;
64-
using tier4_planning_msgs::msg::SafetyFactorArray;
6565
using tier4_rtc_msgs::msg::State;
6666
using unique_identifier_msgs::msg::UUID;
6767
using visualization_msgs::msg::MarkerArray;

planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -22,11 +22,11 @@
2222
#include <autoware_utils/geometry/geometry.hpp>
2323
#include <autoware_utils/geometry/pose_deviation.hpp>
2424

25+
#include <autoware_internal_planning_msgs/msg/planning_factor_array.hpp>
2526
#include <autoware_perception_msgs/msg/predicted_object.hpp>
2627
#include <autoware_perception_msgs/msg/predicted_path.hpp>
2728
#include <geometry_msgs/msg/pose.hpp>
2829
#include <geometry_msgs/msg/twist.hpp>
29-
#include <tier4_planning_msgs/msg/planning_factor_array.hpp>
3030

3131
#include <cmath>
3232
#include <string>
@@ -286,7 +286,7 @@ CollisionCheckDebugPair createObjectDebug(const ExtendedPredictedObject & obj);
286286
void updateCollisionCheckDebugMap(
287287
CollisionCheckDebugMap & debug_map, CollisionCheckDebugPair & object_debug, bool is_safe);
288288

289-
tier4_planning_msgs::msg::SafetyFactorArray to_safety_factor_array(
289+
autoware_internal_planning_msgs::msg::SafetyFactorArray to_safety_factor_array(
290290
const CollisionCheckDebugMap & debug_map);
291291
} // namespace autoware::behavior_path_planner::utils::path_safety_checker
292292

planning/behavior_path_planner/autoware_behavior_path_planner_common/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -45,6 +45,7 @@
4545

4646
<depend>autoware_adapi_v1_msgs</depend>
4747
<depend>autoware_freespace_planning_algorithms</depend>
48+
<depend>autoware_internal_planning_msgs</depend>
4849
<depend>autoware_interpolation</depend>
4950
<depend>autoware_lane_departure_checker</depend>
5051
<depend>autoware_lanelet2_extension</depend>

planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -877,13 +877,13 @@ double calculateRoughDistanceToObjects(
877877
return min_distance;
878878
}
879879

880-
tier4_planning_msgs::msg::SafetyFactorArray to_safety_factor_array(
880+
autoware_internal_planning_msgs::msg::SafetyFactorArray to_safety_factor_array(
881881
const CollisionCheckDebugMap & debug_map)
882882
{
883-
tier4_planning_msgs::msg::SafetyFactorArray safety_factors;
883+
autoware_internal_planning_msgs::msg::SafetyFactorArray safety_factors;
884884
for (const auto & [uuid, data] : debug_map) {
885-
tier4_planning_msgs::msg::SafetyFactor safety_factor;
886-
safety_factor.type = tier4_planning_msgs::msg::SafetyFactor::OBJECT;
885+
autoware_internal_planning_msgs::msg::SafetyFactor safety_factor;
886+
safety_factor.type = autoware_internal_planning_msgs::msg::SafetyFactor::OBJECT;
887887
safety_factor.is_safe = data.is_safe;
888888
safety_factor.object_id = autoware_utils::to_uuid_msg(uuid);
889889
safety_factor.points.push_back(data.current_obj_pose.position);

planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,7 @@
2020
<depend>autoware_behavior_velocity_planner</depend>
2121
<depend>autoware_behavior_velocity_planner_common</depend>
2222
<depend>autoware_behavior_velocity_rtc_interface</depend>
23+
<depend>autoware_internal_planning_msgs</depend>
2324
<depend>autoware_lanelet2_extension</depend>
2425
<depend>autoware_motion_utils</depend>
2526
<depend>autoware_perception_msgs</depend>

planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/decisions.cpp

+6-6
Original file line numberDiff line numberDiff line change
@@ -103,9 +103,9 @@ void BlindSpotModule::reactRTCApprovalByDecision(
103103
const auto stop_pose = path->points.at(decision.stop_line_idx).point.pose;
104104
planning_factor_interface_->add(
105105
path->points, planner_data_->current_odometry->pose, stop_pose, stop_pose,
106-
tier4_planning_msgs::msg::PlanningFactor::STOP, tier4_planning_msgs::msg::SafetyFactorArray{},
107-
true /*is_driving_forward*/, 0.0, 0.0 /*shift distance*/,
108-
"blind_spot(module is judging as UNSAFE)");
106+
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
107+
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0,
108+
0.0 /*shift distance*/, "blind_spot(module is judging as UNSAFE)");
109109
}
110110
return;
111111
}
@@ -137,9 +137,9 @@ void BlindSpotModule::reactRTCApprovalByDecision(
137137
const auto stop_pose = path->points.at(decision.stop_line_idx).point.pose;
138138
planning_factor_interface_->add(
139139
path->points, planner_data_->current_odometry->pose, stop_pose, stop_pose,
140-
tier4_planning_msgs::msg::PlanningFactor::STOP, tier4_planning_msgs::msg::SafetyFactorArray{},
141-
true /*is_driving_forward*/, 0.0, 0.0 /*shift distance*/,
142-
"blind_spot(module is judging as SAFE and RTC is not approved)");
140+
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
141+
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0,
142+
0.0 /*shift distance*/, "blind_spot(module is judging as SAFE and RTC is not approved)");
143143
}
144144
return;
145145
}

planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -26,6 +26,7 @@
2626
<depend>autoware_behavior_velocity_rtc_interface</depend>
2727
<depend>autoware_grid_map_utils</depend>
2828
<depend>autoware_internal_debug_msgs</depend>
29+
<depend>autoware_internal_planning_msgs</depend>
2930
<depend>autoware_interpolation</depend>
3031
<depend>autoware_lanelet2_extension</depend>
3132
<depend>autoware_motion_utils</depend>

planning/behavior_velocity_planner/autoware_behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp

+5-5
Original file line numberDiff line numberDiff line change
@@ -882,8 +882,8 @@ void CrosswalkModule::applySlowDown(
882882
if (slowdown_pose)
883883
planning_factor_interface_->add(
884884
output.points, planner_data_->current_odometry->pose, *slowdown_pose, *slowdown_pose,
885-
tier4_planning_msgs::msg::PlanningFactor::SLOW_DOWN,
886-
tier4_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/,
885+
autoware_internal_planning_msgs::msg::PlanningFactor::SLOW_DOWN,
886+
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/,
887887
safety_slow_down_speed, 0.0 /*shift distance*/, "crosswalk_safety_slowdown_for_approaching");
888888
}
889889

@@ -1365,9 +1365,9 @@ void CrosswalkModule::planStop(
13651365
insertDecelPointWithDebugInfo(stop_factor->stop_pose.position, 0.0, ego_path);
13661366
planning_factor_interface_->add(
13671367
ego_path.points, planner_data_->current_odometry->pose, stop_factor->stop_pose,
1368-
stop_factor->stop_pose, tier4_planning_msgs::msg::PlanningFactor::STOP,
1369-
tier4_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0 /*velocity*/,
1370-
0.0 /*shift distance*/, "crosswalk_stop");
1368+
stop_factor->stop_pose, autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
1369+
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/,
1370+
0.0 /*velocity*/, 0.0 /*shift distance*/, "crosswalk_stop");
13711371
}
13721372

13731373
bool CrosswalkModule::checkRestartSuppression(

planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.cpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -182,8 +182,9 @@ bool DetectionAreaModule::modifyPathVelocity(PathWithLaneId * path)
182182
{
183183
planning_factor_interface_->add(
184184
path->points, planner_data_->current_odometry->pose, stop_pose, stop_pose,
185-
tier4_planning_msgs::msg::PlanningFactor::STOP, tier4_planning_msgs::msg::SafetyFactorArray{},
186-
true /*is_driving_forward*/, 0.0, 0.0 /*shift distance*/, "");
185+
autoware_internal_planning_msgs::msg::PlanningFactor::STOP,
186+
autoware_internal_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0,
187+
0.0 /*shift distance*/, "");
187188
}
188189

189190
return true;

planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,7 @@
2323
<depend>autoware_behavior_velocity_planner_common</depend>
2424
<depend>autoware_behavior_velocity_rtc_interface</depend>
2525
<depend>autoware_internal_debug_msgs</depend>
26+
<depend>autoware_internal_planning_msgs</depend>
2627
<depend>autoware_interpolation</depend>
2728
<depend>autoware_lanelet2_extension</depend>
2829
<depend>autoware_motion_utils</depend>

0 commit comments

Comments
 (0)