Skip to content

Commit

Permalink
Revert "perf(out_of_lane): downsample the trajectory to improve perfo…
Browse files Browse the repository at this point in the history
…rmance (autowarefoundation#7691)"

This reverts commit 8444a9e.
  • Loading branch information
maxime-clem committed Jun 27, 2024
1 parent f211565 commit a2d9311
Show file tree
Hide file tree
Showing 6 changed files with 57 additions and 54 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ size_t calculateStartIndex(
/// @param[in] start_idx starting index of the input trajectory
/// @param[in] factor factor used for downsampling
/// @return downsampled trajectory
TrajectoryPoints downsample_trajectory(
TrajectoryPoints downsampleTrajectory(
const TrajectoryPoints & trajectory, const size_t start_idx, const int factor);

/// @brief recalculate the steering angle of the trajectory
Expand Down Expand Up @@ -123,6 +123,16 @@ std::vector<autoware::motion_velocity_planner::SlowdownInterval> calculate_slowd
const std::vector<multi_linestring_t> & projections, const std::vector<polygon_t> & footprints,
ProjectionParameters & projection_params, const VelocityParameters & velocity_params,
autoware::motion_utils::VirtualWalls & virtual_walls);

/// @brief copy the velocity profile of a downsampled trajectory to the original trajectory
/// @param[in] downsampled_trajectory downsampled trajectory
/// @param[in] trajectory input trajectory
/// @param[in] start_idx starting index of the downsampled trajectory relative to the input
/// @param[in] factor downsampling factor
/// @return input trajectory with the velocity profile of the downsampled trajectory
TrajectoryPoints copyDownsampledVelocity(
const TrajectoryPoints & downsampled_traj, TrajectoryPoints trajectory, const size_t start_idx,
const int factor);
} // namespace autoware::motion_velocity_planner::obstacle_velocity_limiter

#endif // OBSTACLE_VELOCITY_LIMITER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,6 @@

#include <autoware/motion_utils/marker/virtual_wall_marker_creator.hpp>
#include <autoware/motion_utils/trajectory/trajectory.hpp>
#include <autoware/motion_velocity_planner_common/trajectory_preprocessing.hpp>
#include <autoware/universe_utils/ros/update_param.hpp>
#include <autoware/universe_utils/system/stop_watch.hpp>
#include <autoware_vehicle_info_utils/vehicle_info_utils.hpp>
Expand Down Expand Up @@ -160,7 +159,7 @@ VelocityPlanningResult ObstacleVelocityLimiterModule::plan(
const auto end_idx = obstacle_velocity_limiter::calculateEndIndex(
original_traj_points, start_idx, preprocessing_params_.max_length,
preprocessing_params_.max_duration);
auto downsampled_traj_points = downsample_trajectory(
auto downsampled_traj_points = obstacle_velocity_limiter::downsampleTrajectory(
original_traj_points, start_idx, end_idx, preprocessing_params_.downsample_factor);
obstacle_velocity_limiter::ObstacleMasks obstacle_masks;
const auto preprocessing_us = stopwatch.toc("preprocessing");
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,17 @@ size_t calculateEndIndex(
return idx;
}

TrajectoryPoints downsampleTrajectory(
const TrajectoryPoints & trajectory, const size_t start_idx, const size_t end_idx,
const int factor)
{
if (factor < 1) return trajectory;
TrajectoryPoints downsampled_traj;
downsampled_traj.reserve((end_idx - start_idx) / factor);
for (size_t i = start_idx; i <= end_idx; i += factor) downsampled_traj.push_back(trajectory[i]);
return downsampled_traj;
}

void calculateSteeringAngles(TrajectoryPoints & trajectory, const double wheel_base)
{
auto prev_point = trajectory.front();
Expand All @@ -71,4 +82,16 @@ void calculateSteeringAngles(TrajectoryPoints & trajectory, const double wheel_b
std::atan2(wheel_base * d_heading, point.longitudinal_velocity_mps * dt);
}
}

TrajectoryPoints copyDownsampledVelocity(
const TrajectoryPoints & downsampled_traj, TrajectoryPoints trajectory, const size_t start_idx,
const int factor)
{
const auto size = std::min(downsampled_traj.size(), trajectory.size());
for (size_t i = 0; i < size; ++i) {
trajectory[start_idx + i * factor].longitudinal_velocity_mps =
downsampled_traj[i].longitudinal_velocity_mps;
}
return trajectory;
}
} // namespace autoware::motion_velocity_planner::obstacle_velocity_limiter
Original file line number Diff line number Diff line change
Expand Up @@ -37,11 +37,31 @@ size_t calculateEndIndex(
const TrajectoryPoints & trajectory, const size_t start_idx, const double max_length,
const double max_duration);

/// @brief downsample a trajectory, reducing its number of points by the given factor
/// @param[in] trajectory input trajectory
/// @param[in] start_idx starting index of the input trajectory
/// @param[in] end_idx ending index of the input trajectory
/// @param[in] factor factor used for downsampling
/// @return downsampled trajectory
TrajectoryPoints downsampleTrajectory(
const TrajectoryPoints & trajectory, const size_t start_idx, const size_t end_idx,
const int factor);

/// @brief recalculate the steering angle of the trajectory
/// @details uses the change in headings for calculation
/// @param[inout] trajectory input trajectory
/// @param[in] wheel_base wheel base of the vehicle
void calculateSteeringAngles(TrajectoryPoints & trajectory, const double wheel_base);

/// @brief copy the velocity profile of a downsampled trajectory to the original trajectory
/// @param[in] downsampled_trajectory downsampled trajectory
/// @param[in] trajectory input trajectory
/// @param[in] start_idx starting index of the downsampled trajectory relative to the input
/// @param[in] factor downsampling factor
/// @return input trajectory with the velocity profile of the downsampled trajectory
TrajectoryPoints copyDownsampledVelocity(
const TrajectoryPoints & downsampled_traj, TrajectoryPoints trajectory, const size_t start_idx,
const int factor);
} // namespace autoware::motion_velocity_planner::obstacle_velocity_limiter

#endif // TRAJECTORY_PREPROCESSING_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,6 @@

#include <autoware/motion_utils/trajectory/interpolation.hpp>
#include <autoware/motion_utils/trajectory/trajectory.hpp>
#include <autoware/motion_velocity_planner_common/trajectory_preprocessing.hpp>
#include <autoware/universe_utils/ros/parameter.hpp>
#include <autoware/universe_utils/ros/update_param.hpp>
#include <autoware/universe_utils/system/stop_watch.hpp>
Expand Down Expand Up @@ -161,11 +160,9 @@ VelocityPlanningResult OutOfLaneModule::plan(
stopwatch.tic();
out_of_lane::EgoData ego_data;
ego_data.pose = planner_data->current_odometry.pose.pose;
const auto start_idx =
ego_data.trajectory_points = ego_trajectory_points;
ego_data.first_trajectory_idx =
autoware::motion_utils::findNearestSegmentIndex(ego_trajectory_points, ego_data.pose.position);
ego_data.trajectory_points =
downsample_trajectory(ego_trajectory_points, start_idx, ego_trajectory_points.size(), 10);
ego_data.first_trajectory_idx = 0;
ego_data.velocity = planner_data->current_odometry.twist.twist.linear.x;
ego_data.max_decel = planner_data->velocity_smoother_->getMinDecel();
stopwatch.tic("calculate_trajectory_footprints");
Expand Down

This file was deleted.

0 comments on commit a2d9311

Please sign in to comment.