Skip to content

Commit 4c03b8d

Browse files
feat(pid_longitudinal_controller): add new slope compensation mode trajectory_goal_adaptive (#9705)
Signed-off-by: yuki-takagi-66 <yuki.takagi@tier4.jp>
1 parent a7314b6 commit 4c03b8d

File tree

4 files changed

+30
-12
lines changed

4 files changed

+30
-12
lines changed

control/autoware_pid_longitudinal_controller/README.md

+2
Original file line numberDiff line numberDiff line change
@@ -68,6 +68,8 @@ There are two sources of the slope information, which can be switched by a param
6868
- Cons: z-coordinates of high-precision map is needed.
6969
- Cons: Does not support free space planning (for now)
7070

71+
We also offer the options to switch between these, depending on driving conditions.
72+
7173
**Notation:** This function works correctly only in a vehicle system that does not have acceleration feedback in the low-level control system.
7274

7375
This compensation adds gravity correction to the target acceleration, resulting in an output value that is no longer equal to the target acceleration that the autonomous driving system desires. Therefore, it conflicts with the role of the acceleration feedback in the low-level controller.

control/autoware_pid_longitudinal_controller/config/autoware_pid_longitudinal_controller.param.yaml

+1-1
Original file line numberDiff line numberDiff line change
@@ -74,7 +74,7 @@
7474

7575
# slope compensation
7676
lpf_pitch_gain: 0.95
77-
slope_source: "raw_pitch" # raw_pitch, trajectory_pitch or trajectory_adaptive
77+
slope_source: "trajectory_goal_adaptive" # raw_pitch, trajectory_pitch, trajectory_adaptive or trajectory_goal_adaptive
7878
adaptive_trajectory_velocity_th: 1.0
7979
max_pitch_rad: 0.1
8080
min_pitch_rad: -0.1

control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/pid_longitudinal_controller.hpp

+6-1
Original file line numberDiff line numberDiff line change
@@ -204,7 +204,12 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro
204204
double m_max_acc_cmd_diff;
205205

206206
// slope compensation
207-
enum class SlopeSource { RAW_PITCH = 0, TRAJECTORY_PITCH, TRAJECTORY_ADAPTIVE };
207+
enum class SlopeSource {
208+
RAW_PITCH = 0,
209+
TRAJECTORY_PITCH,
210+
TRAJECTORY_ADAPTIVE,
211+
TRAJECTORY_GOAL_ADAPTIVE
212+
};
208213
SlopeSource m_slope_source{SlopeSource::RAW_PITCH};
209214
double m_adaptive_trajectory_velocity_th;
210215
std::shared_ptr<LowpassFilter1d> m_lpf_pitch{nullptr};

control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp

+21-10
Original file line numberDiff line numberDiff line change
@@ -196,6 +196,8 @@ PidLongitudinalController::PidLongitudinalController(
196196
m_slope_source = SlopeSource::TRAJECTORY_PITCH;
197197
} else if (slope_source == "trajectory_adaptive") {
198198
m_slope_source = SlopeSource::TRAJECTORY_ADAPTIVE;
199+
} else if (slope_source == "trajectory_goal_adaptive") {
200+
m_slope_source = SlopeSource::TRAJECTORY_GOAL_ADAPTIVE;
199201
} else {
200202
RCLCPP_ERROR(logger_, "Slope source is not valid. Using raw_pitch option as default");
201203
m_slope_source = SlopeSource::RAW_PITCH;
@@ -529,35 +531,44 @@ PidLongitudinalController::ControlData PidLongitudinalController::getControlData
529531
// NOTE: getPitchByTraj() calculates the pitch angle as defined in
530532
// ../media/slope_definition.drawio.svg while getPitchByPose() is not, so `raw_pitch` is reversed
531533
const double raw_pitch = (-1.0) * longitudinal_utils::getPitchByPose(current_pose.orientation);
534+
m_lpf_pitch->filter(raw_pitch);
532535
const double traj_pitch = longitudinal_utils::getPitchByTraj(
533536
control_data.interpolated_traj, control_data.target_idx, m_wheel_base);
534537

535538
if (m_slope_source == SlopeSource::RAW_PITCH) {
536-
control_data.slope_angle = m_lpf_pitch->filter(raw_pitch);
539+
control_data.slope_angle = m_lpf_pitch->getValue();
537540
} else if (m_slope_source == SlopeSource::TRAJECTORY_PITCH) {
538541
control_data.slope_angle = traj_pitch;
539-
} else if (m_slope_source == SlopeSource::TRAJECTORY_ADAPTIVE) {
542+
} else if (
543+
m_slope_source == SlopeSource::TRAJECTORY_ADAPTIVE ||
544+
m_slope_source == SlopeSource::TRAJECTORY_GOAL_ADAPTIVE) {
540545
// if velocity is high, use target idx for slope, otherwise, use raw_pitch
541-
if (control_data.current_motion.vel > m_adaptive_trajectory_velocity_th) {
542-
control_data.slope_angle = traj_pitch;
543-
m_lpf_pitch->filter(raw_pitch);
544-
} else {
545-
control_data.slope_angle = m_lpf_pitch->filter(raw_pitch);
546-
}
546+
const bool is_vel_slow = control_data.current_motion.vel < m_adaptive_trajectory_velocity_th &&
547+
m_slope_source == SlopeSource::TRAJECTORY_ADAPTIVE;
548+
549+
const double goal_dist = autoware::motion_utils::calcSignedArcLength(
550+
control_data.interpolated_traj.points, current_pose.position,
551+
control_data.interpolated_traj.points.size() - 1);
552+
const bool is_close_to_trajectory_end =
553+
goal_dist < m_wheel_base && m_slope_source == SlopeSource::TRAJECTORY_GOAL_ADAPTIVE;
554+
555+
control_data.slope_angle =
556+
(is_close_to_trajectory_end || is_vel_slow) ? m_lpf_pitch->getValue() : traj_pitch;
557+
547558
if (m_previous_slope_angle.has_value()) {
548559
constexpr double gravity_const = 9.8;
549560
control_data.slope_angle = std::clamp(
550561
control_data.slope_angle,
551562
m_previous_slope_angle.value() + m_min_jerk * control_data.dt / gravity_const,
552563
m_previous_slope_angle.value() + m_max_jerk * control_data.dt / gravity_const);
553564
}
565+
m_previous_slope_angle = control_data.slope_angle;
554566
} else {
555567
RCLCPP_ERROR_THROTTLE(
556568
logger_, *clock_, 3000, "Slope source is not valid. Using raw_pitch option as default");
557-
control_data.slope_angle = m_lpf_pitch->filter(raw_pitch);
569+
control_data.slope_angle = m_lpf_pitch->getValue();
558570
}
559571

560-
m_previous_slope_angle = control_data.slope_angle;
561572
updatePitchDebugValues(control_data.slope_angle, traj_pitch, raw_pitch, m_lpf_pitch->getValue());
562573

563574
return control_data;

0 commit comments

Comments
 (0)