|
26 | 26 | #include <pcl/filters/voxel_grid.h>
|
27 | 27 |
|
28 | 28 | #include <algorithm>
|
| 29 | +#include <limits> |
29 | 30 | #include <string>
|
30 | 31 |
|
31 | 32 | namespace behavior_velocity_planner
|
@@ -312,6 +313,40 @@ void calculateMinAndMaxVelFromCovariance(
|
312 | 313 | dynamic_obstacle.max_velocity_mps = max_velocity;
|
313 | 314 | }
|
314 | 315 |
|
| 316 | +double convertDurationToDouble(const builtin_interfaces::msg::Duration & duration) |
| 317 | +{ |
| 318 | + return duration.sec + duration.nanosec / 1e9; |
| 319 | +} |
| 320 | + |
| 321 | +// Create a path leading up to a specified prediction time |
| 322 | +std::vector<geometry_msgs::msg::Pose> createPathToPredictionTime( |
| 323 | + const autoware_auto_perception_msgs::msg::PredictedPath & predicted_path, double prediction_time) |
| 324 | +{ |
| 325 | + // Calculate the number of poses to include based on the prediction time and the time step between |
| 326 | + // poses |
| 327 | + const double time_step_seconds = convertDurationToDouble(predicted_path.time_step); |
| 328 | + if (time_step_seconds < std::numeric_limits<double>::epsilon()) { |
| 329 | + // Handle the case where time_step_seconds is zero or too close to zero |
| 330 | + RCLCPP_WARN_STREAM( |
| 331 | + rclcpp::get_logger("run_out: createPathToPredictionTime"), |
| 332 | + "time_step of the path is too close to zero. Use the input path"); |
| 333 | + const std::vector<geometry_msgs::msg::Pose> input_path( |
| 334 | + predicted_path.path.begin(), predicted_path.path.end()); |
| 335 | + return input_path; |
| 336 | + } |
| 337 | + const size_t poses_to_include = |
| 338 | + std::min(static_cast<size_t>(prediction_time / time_step_seconds), predicted_path.path.size()); |
| 339 | + |
| 340 | + // Construct the path to the specified prediction time |
| 341 | + std::vector<geometry_msgs::msg::Pose> path_to_prediction_time; |
| 342 | + path_to_prediction_time.reserve(poses_to_include); |
| 343 | + for (size_t i = 0; i < poses_to_include; ++i) { |
| 344 | + path_to_prediction_time.push_back(predicted_path.path[i]); |
| 345 | + } |
| 346 | + |
| 347 | + return path_to_prediction_time; |
| 348 | +} |
| 349 | + |
315 | 350 | } // namespace
|
316 | 351 |
|
317 | 352 | DynamicObstacleCreatorForObject::DynamicObstacleCreatorForObject(
|
@@ -343,8 +378,7 @@ std::vector<DynamicObstacle> DynamicObstacleCreatorForObject::createDynamicObsta
|
343 | 378 | for (const auto & path : predicted_object.kinematics.predicted_paths) {
|
344 | 379 | PredictedPath predicted_path;
|
345 | 380 | predicted_path.confidence = path.confidence;
|
346 |
| - predicted_path.path.resize(path.path.size()); |
347 |
| - std::copy(path.path.cbegin(), path.path.cend(), predicted_path.path.begin()); |
| 381 | + predicted_path.path = createPathToPredictionTime(path, param_.max_prediction_time); |
348 | 382 |
|
349 | 383 | dynamic_obstacle.predicted_paths.emplace_back(predicted_path);
|
350 | 384 | }
|
|
0 commit comments