File tree 3 files changed +14
-13
lines changed
behavior_path_lane_change_module/src/utils
behavior_path_planner_common
include/behavior_path_planner_common/utils/path_safety_checker
src/utils/path_safety_checker
3 files changed +14
-13
lines changed Original file line number Diff line number Diff line change @@ -1112,12 +1112,7 @@ ExtendedPredictedObject transform(
1112
1112
[[maybe_unused]] const BehaviorPathPlannerParameters & common_parameters,
1113
1113
const LaneChangeParameters & lane_change_parameters, const bool check_at_prepare_phase)
1114
1114
{
1115
- ExtendedPredictedObject extended_object;
1116
- extended_object.uuid = object.object_id ;
1117
- extended_object.initial_pose = object.kinematics .initial_pose_with_covariance ;
1118
- extended_object.initial_twist = object.kinematics .initial_twist_with_covariance ;
1119
- extended_object.initial_acceleration = object.kinematics .initial_acceleration_with_covariance ;
1120
- extended_object.shape = object.shape ;
1115
+ ExtendedPredictedObject extended_object (object);
1121
1116
1122
1117
const auto & time_resolution = lane_change_parameters.prediction_time_resolution ;
1123
1118
const auto & prepare_duration = lane_change_parameters.lane_change_prepare_duration ;
Original file line number Diff line number Diff line change 31
31
namespace behavior_path_planner ::utils::path_safety_checker
32
32
{
33
33
34
+ using autoware_auto_perception_msgs::msg::PredictedObject;
34
35
using geometry_msgs::msg::Pose;
35
36
using geometry_msgs::msg::Twist;
36
37
using tier4_autoware_utils::Polygon2d;
@@ -79,6 +80,17 @@ struct ExtendedPredictedObject
79
80
autoware_auto_perception_msgs::msg::Shape shape;
80
81
std::vector<autoware_auto_perception_msgs::msg::ObjectClassification> classification;
81
82
std::vector<PredictedPathWithPolygon> predicted_paths;
83
+
84
+ ExtendedPredictedObject () = default ;
85
+ explicit ExtendedPredictedObject (const PredictedObject & object)
86
+ : uuid(object.object_id),
87
+ initial_pose(object.kinematics.initial_pose_with_covariance),
88
+ initial_twist(object.kinematics.initial_twist_with_covariance),
89
+ initial_acceleration(object.kinematics.initial_acceleration_with_covariance),
90
+ shape(object.shape),
91
+ classification(object.classification)
92
+ {
93
+ }
82
94
};
83
95
using ExtendedPredictedObjects = std::vector<ExtendedPredictedObject>;
84
96
Original file line number Diff line number Diff line change @@ -289,13 +289,7 @@ ExtendedPredictedObject transform(
289
289
const PredictedObject & object, const double safety_check_time_horizon,
290
290
const double safety_check_time_resolution)
291
291
{
292
- ExtendedPredictedObject extended_object;
293
- extended_object.uuid = object.object_id ;
294
- extended_object.initial_pose = object.kinematics .initial_pose_with_covariance ;
295
- extended_object.initial_twist = object.kinematics .initial_twist_with_covariance ;
296
- extended_object.initial_acceleration = object.kinematics .initial_acceleration_with_covariance ;
297
- extended_object.shape = object.shape ;
298
- extended_object.classification = object.classification ;
292
+ ExtendedPredictedObject extended_object (object);
299
293
300
294
const auto obj_velocity = extended_object.initial_twist .twist .linear .x ;
301
295
You can’t perform that action at this time.
0 commit comments