Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(autoware_motion_utils): set zero velocity after stop in resample trajectory #8768

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
17 changes: 17 additions & 0 deletions common/autoware_motion_utils/src/resample/resample.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2022 Tier IV, Inc.

Check notice on line 1 in common/autoware_motion_utils/src/resample/resample.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Overall Code Complexity

The mean cyclomatic complexity increases from 10.00 to 10.30, threshold = 4. This file has many conditional statements (e.g. if, for, while) across its implementation, leading to lower code health. Avoid adding more conditionals.

Check warning on line 1 in common/autoware_motion_utils/src/resample/resample.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

resampleTrajectory already has high cyclomatic complexity, and now it increases in Lines of Code from 95 to 105. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand All @@ -21,6 +21,8 @@
#include "interpolation/spline_interpolation.hpp"
#include "interpolation/zero_order_hold.hpp"

#include <cstdlib>

namespace autoware::motion_utils
{
std::vector<geometry_msgs::msg::Point> resamplePointVector(
Expand Down Expand Up @@ -601,22 +603,37 @@
rear_wheel_angle.push_back(input_trajectory.points.front().rear_wheel_angle_rad);
time_from_start.push_back(
rclcpp::Duration(input_trajectory.points.front().time_from_start).seconds());

for (size_t i = 1; i < input_trajectory.points.size(); ++i) {
const auto & prev_pt = input_trajectory.points.at(i - 1);
const auto & curr_pt = input_trajectory.points.at(i);
const double ds =
autoware::universe_utils::calcDistance2d(prev_pt.pose.position, curr_pt.pose.position);

input_arclength.push_back(ds + input_arclength.back());
input_pose.push_back(curr_pt.pose);
v_lon.push_back(curr_pt.longitudinal_velocity_mps);
v_lat.push_back(curr_pt.lateral_velocity_mps);
heading_rate.push_back(curr_pt.heading_rate_rps);
acceleration.push_back(curr_pt.acceleration_mps2);
front_wheel_angle.push_back(curr_pt.front_wheel_angle_rad);
rear_wheel_angle.push_back(curr_pt.rear_wheel_angle_rad);
time_from_start.push_back(rclcpp::Duration(curr_pt.time_from_start).seconds());
}

// Set Zero Velocity After Stop Point
// If the longitudinal velocity is zero, set the velocity to zero after that point.
bool stop_point_found_in_v_lon = false;
constexpr double epsilon = 1e-4;
for (size_t i = 0; i < v_lon.size(); ++i) {
if (std::abs(v_lon.at(i)) < epsilon) {
stop_point_found_in_v_lon = true;
}
if (stop_point_found_in_v_lon) {
v_lon.at(i) = 0.0;
}
}

Check warning on line 636 in common/autoware_motion_utils/src/resample/resample.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

resampleTrajectory increases in cyclomatic complexity from 9 to 12, threshold = 9. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.
// Interpolate
const auto lerp = [&](const auto & input) {
return interpolation::lerp(input_arclength, input, resampled_arclength);
Expand Down
Loading
Loading