Skip to content

Commit 19af48e

Browse files
feat(pid_long, vehicle_cmd_gate)!: quick pedal change (#1425)
* feat(simple_planning_simulator): add new vehicle model with falling down (autowarefoundation#7651) * add new vehicle model Signed-off-by: Yuki Takagi <yuki.takagi@tier4.jp> * refactor(vehicle_cmd_gate)!: delete rate limit skipping function for vehicle departure (autowarefoundation#7720) * delete a fucntion block. More appropriate function can be achieved by the parameter settings. * add notation to readme --------- Signed-off-by: Yuki Takagi <yuki.takagi@tier4.jp> * feat(pid_longitudinal_controller): re-organize diff limit structure and fix state change condition (autowarefoundation#7718) change diff limit structure change stopped condition define a new param Signed-off-by: Yuki Takagi <yuki.takagi@tier4.jp> --------- Signed-off-by: Yuki Takagi <yuki.takagi@tier4.jp>
1 parent 664b2e1 commit 19af48e

File tree

15 files changed

+487
-141
lines changed

15 files changed

+487
-141
lines changed

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

+2-2
Original file line numberDiff line numberDiff line change
@@ -183,7 +183,6 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro
183183
{
184184
double vel;
185185
double acc;
186-
double jerk;
187186
};
188187
StoppedStateParams m_stopped_state_params;
189188

@@ -203,6 +202,7 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro
203202
// jerk limit
204203
double m_max_jerk;
205204
double m_min_jerk;
205+
double m_max_acc_cmd_diff;
206206

207207
// slope compensation
208208
enum class SlopeSource { RAW_PITCH = 0, TRAJECTORY_PITCH, TRAJECTORY_ADAPTIVE };
@@ -291,7 +291,7 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro
291291
* @brief calculate control command in emergency state
292292
* @param [in] dt time between previous and current one
293293
*/
294-
Motion calcEmergencyCtrlCmd(const double dt) const;
294+
Motion calcEmergencyCtrlCmd(const double dt);
295295

296296
/**
297297
* @brief update control state according to the current situation

control/autoware_pid_longitudinal_controller/param/longitudinal_controller_defaults.param.yaml

+3-3
Original file line numberDiff line numberDiff line change
@@ -53,12 +53,11 @@
5353

5454
# stopped state
5555
stopped_vel: 0.0
56-
stopped_acc: -3.4
57-
stopped_jerk: -5.0
56+
stopped_acc: -3.4 # denotes pedal position
5857

5958
# emergency state
6059
emergency_vel: 0.0
61-
emergency_acc: -5.0
60+
emergency_acc: -5.0 # denotes acceleration
6261
emergency_jerk: -3.0
6362

6463
# acceleration limit
@@ -68,6 +67,7 @@
6867
# jerk limit
6968
max_jerk: 2.0
7069
min_jerk: -5.0
70+
max_acc_cmd_diff: 50.0 # [m/s^2 * s^-1]
7171

7272
# slope compensation
7373
lpf_pitch_gain: 0.95

control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp

+87-77
Original file line numberDiff line numberDiff line change
@@ -150,9 +150,8 @@ PidLongitudinalController::PidLongitudinalController(rclcpp::Node & node)
150150
// parameters for stop state
151151
{
152152
auto & p = m_stopped_state_params;
153-
p.vel = node.declare_parameter<double>("stopped_vel"); // [m/s]
154-
p.acc = node.declare_parameter<double>("stopped_acc"); // [m/s^2]
155-
p.jerk = node.declare_parameter<double>("stopped_jerk"); // [m/s^3]
153+
p.vel = node.declare_parameter<double>("stopped_vel"); // [m/s]
154+
p.acc = node.declare_parameter<double>("stopped_acc"); // [m/s^2]
156155
}
157156

158157
// parameters for emergency state
@@ -168,8 +167,9 @@ PidLongitudinalController::PidLongitudinalController(rclcpp::Node & node)
168167
m_min_acc = node.declare_parameter<double>("min_acc"); // [m/s^2]
169168

170169
// parameters for jerk limit
171-
m_max_jerk = node.declare_parameter<double>("max_jerk"); // [m/s^3]
172-
m_min_jerk = node.declare_parameter<double>("min_jerk"); // [m/s^3]
170+
m_max_jerk = node.declare_parameter<double>("max_jerk"); // [m/s^3]
171+
m_min_jerk = node.declare_parameter<double>("min_jerk"); // [m/s^3]
172+
m_max_acc_cmd_diff = node.declare_parameter<double>("max_acc_cmd_diff"); // [m/s^3]
173173

174174
// parameters for slope compensation
175175
m_adaptive_trajectory_velocity_th =
@@ -353,7 +353,6 @@ rcl_interfaces::msg::SetParametersResult PidLongitudinalController::paramCallbac
353353
auto & p = m_stopped_state_params;
354354
update_param("stopped_vel", p.vel);
355355
update_param("stopped_acc", p.acc);
356-
update_param("stopped_jerk", p.jerk);
357356
}
358357

359358
// emergency state
@@ -370,6 +369,7 @@ rcl_interfaces::msg::SetParametersResult PidLongitudinalController::paramCallbac
370369
// jerk limit
371370
update_param("max_jerk", m_max_jerk);
372371
update_param("min_jerk", m_min_jerk);
372+
update_param("max_acc_cmd_diff", m_max_acc_cmd_diff);
373373

374374
// slope compensation
375375
update_param("max_pitch_rad", m_max_pitch_rad);
@@ -565,26 +565,30 @@ PidLongitudinalController::ControlData PidLongitudinalController::getControlData
565565
return control_data;
566566
}
567567

568-
PidLongitudinalController::Motion PidLongitudinalController::calcEmergencyCtrlCmd(
569-
const double dt) const
568+
PidLongitudinalController::Motion PidLongitudinalController::calcEmergencyCtrlCmd(const double dt)
570569
{
571570
// These accelerations are without slope compensation
572571
const auto & p = m_emergency_state_params;
573-
const double vel =
574-
longitudinal_utils::applyDiffLimitFilter(p.vel, m_prev_raw_ctrl_cmd.vel, dt, p.acc);
575-
const double acc =
576-
longitudinal_utils::applyDiffLimitFilter(p.acc, m_prev_raw_ctrl_cmd.acc, dt, p.jerk);
572+
Motion raw_ctrl_cmd{p.vel, p.acc};
573+
574+
raw_ctrl_cmd.vel =
575+
longitudinal_utils::applyDiffLimitFilter(raw_ctrl_cmd.vel, m_prev_raw_ctrl_cmd.vel, dt, p.acc);
576+
raw_ctrl_cmd.acc = std::clamp(raw_ctrl_cmd.acc, m_min_acc, m_max_acc);
577+
m_debug_values.setValues(DebugValues::TYPE::ACC_CMD_ACC_LIMITED, raw_ctrl_cmd.acc);
578+
raw_ctrl_cmd.acc =
579+
longitudinal_utils::applyDiffLimitFilter(raw_ctrl_cmd.acc, m_prev_raw_ctrl_cmd.acc, dt, p.jerk);
580+
m_debug_values.setValues(DebugValues::TYPE::ACC_CMD_JERK_LIMITED, raw_ctrl_cmd.acc);
577581

578582
RCLCPP_ERROR_THROTTLE(
579-
logger_, *clock_, 3000, "[Emergency stop] vel: %3.3f, acc: %3.3f", vel, acc);
583+
logger_, *clock_, 3000, "[Emergency stop] vel: %3.3f, acc: %3.3f", raw_ctrl_cmd.vel,
584+
raw_ctrl_cmd.acc);
580585

581-
return Motion{vel, acc};
586+
return raw_ctrl_cmd;
582587
}
583588

584589
void PidLongitudinalController::updateControlState(const ControlData & control_data)
585590
{
586591
const double current_vel = control_data.current_motion.vel;
587-
const double current_acc = control_data.current_motion.acc;
588592
const double stop_dist = control_data.stop_dist;
589593

590594
// flags for state transition
@@ -599,8 +603,8 @@ void PidLongitudinalController::updateControlState(const ControlData & control_d
599603

600604
const bool stopping_condition = stop_dist < p.stopping_state_stop_dist;
601605

602-
const bool is_stopped = std::abs(current_vel) < p.stopped_state_entry_vel &&
603-
std::abs(current_acc) < p.stopped_state_entry_acc;
606+
const bool is_stopped = std::abs(current_vel) < p.stopped_state_entry_vel;
607+
604608
// Case where the ego slips in the opposite direction of the gear due to e.g. a slope is also
605609
// considered as a stop
606610
const bool is_not_running = [&]() {
@@ -701,7 +705,7 @@ void PidLongitudinalController::updateControlState(const ControlData & control_d
701705
m_pid_vel.reset();
702706
m_lpf_vel_error->reset(0.0);
703707
// prevent the car from taking a long time to start to move
704-
m_prev_ctrl_cmd.acc = std::max(0.0, m_prev_ctrl_cmd.acc);
708+
m_prev_ctrl_cmd.acc = std::max(0.0, m_prev_raw_ctrl_cmd.acc);
705709
return changeState(ControlState::DRIVE);
706710
}
707711
return;
@@ -747,8 +751,6 @@ void PidLongitudinalController::updateControlState(const ControlData & control_d
747751

748752
m_pid_vel.reset();
749753
m_lpf_vel_error->reset(0.0);
750-
// prevent the car from taking a long time to start to move
751-
m_prev_ctrl_cmd.acc = std::max(0.0, m_prev_ctrl_cmd.acc);
752754
return changeState(ControlState::DRIVE);
753755
}
754756

@@ -780,55 +782,85 @@ PidLongitudinalController::Motion PidLongitudinalController::calcCtrlCmd(
780782
const size_t target_idx = control_data.target_idx;
781783

782784
// velocity and acceleration command
783-
Motion raw_ctrl_cmd{
785+
Motion ctrl_cmd_as_pedal_pos{
784786
control_data.interpolated_traj.points.at(target_idx).longitudinal_velocity_mps,
785787
control_data.interpolated_traj.points.at(target_idx).acceleration_mps2};
786788

787-
if (m_control_state == ControlState::DRIVE) {
788-
raw_ctrl_cmd.vel =
789-
control_data.interpolated_traj.points.at(control_data.target_idx).longitudinal_velocity_mps;
790-
raw_ctrl_cmd.acc = applyVelocityFeedback(control_data);
791-
raw_ctrl_cmd = keepBrakeBeforeStop(control_data, raw_ctrl_cmd, target_idx);
789+
if (m_control_state == ControlState::STOPPED) {
790+
const auto & p = m_stopped_state_params;
791+
ctrl_cmd_as_pedal_pos.vel = p.vel;
792+
ctrl_cmd_as_pedal_pos.acc = p.acc;
792793

793-
RCLCPP_DEBUG(
794-
logger_,
795-
"[feedback control] vel: %3.3f, acc: %3.3f, dt: %3.3f, v_curr: %3.3f, v_ref: %3.3f "
796-
"feedback_ctrl_cmd.ac: %3.3f",
797-
raw_ctrl_cmd.vel, raw_ctrl_cmd.acc, control_data.dt, control_data.current_motion.vel,
798-
control_data.interpolated_traj.points.at(control_data.target_idx).longitudinal_velocity_mps,
799-
raw_ctrl_cmd.acc);
800-
} else if (m_control_state == ControlState::STOPPING) {
801-
raw_ctrl_cmd.acc = m_smooth_stop.calculate(
802-
control_data.stop_dist, control_data.current_motion.vel, control_data.current_motion.acc,
803-
m_vel_hist, m_delay_compensation_time);
804-
raw_ctrl_cmd.vel = m_stopped_state_params.vel;
794+
m_prev_raw_ctrl_cmd.vel = 0.0;
795+
m_prev_raw_ctrl_cmd.acc = 0.0;
796+
797+
m_debug_values.setValues(DebugValues::TYPE::ACC_CMD_ACC_LIMITED, ctrl_cmd_as_pedal_pos.acc);
798+
m_debug_values.setValues(DebugValues::TYPE::ACC_CMD_JERK_LIMITED, ctrl_cmd_as_pedal_pos.acc);
799+
m_debug_values.setValues(DebugValues::TYPE::ACC_CMD_SLOPE_APPLIED, ctrl_cmd_as_pedal_pos.acc);
805800

806801
RCLCPP_DEBUG(
807-
logger_, "[smooth stop]: Smooth stopping. vel: %3.3f, acc: %3.3f", raw_ctrl_cmd.vel,
808-
raw_ctrl_cmd.acc);
809-
} else if (m_control_state == ControlState::STOPPED) {
810-
// This acceleration is without slope compensation
811-
const auto & p = m_stopped_state_params;
812-
raw_ctrl_cmd.vel = p.vel;
813-
raw_ctrl_cmd.acc = longitudinal_utils::applyDiffLimitFilter(
814-
p.acc, m_prev_raw_ctrl_cmd.acc, control_data.dt, p.jerk);
802+
logger_, "[Stopped]. vel: %3.3f, acc: %3.3f", ctrl_cmd_as_pedal_pos.vel,
803+
ctrl_cmd_as_pedal_pos.acc);
804+
} else {
805+
Motion raw_ctrl_cmd{
806+
control_data.interpolated_traj.points.at(target_idx).longitudinal_velocity_mps,
807+
control_data.interpolated_traj.points.at(target_idx).acceleration_mps2};
808+
if (m_control_state == ControlState::EMERGENCY) {
809+
raw_ctrl_cmd = calcEmergencyCtrlCmd(control_data.dt);
810+
} else {
811+
if (m_control_state == ControlState::DRIVE) {
812+
raw_ctrl_cmd.vel = control_data.interpolated_traj.points.at(control_data.target_idx)
813+
.longitudinal_velocity_mps;
814+
raw_ctrl_cmd.acc = applyVelocityFeedback(control_data);
815+
raw_ctrl_cmd = keepBrakeBeforeStop(control_data, raw_ctrl_cmd, target_idx);
816+
817+
RCLCPP_DEBUG(
818+
logger_,
819+
"[feedback control] vel: %3.3f, acc: %3.3f, dt: %3.3f, v_curr: %3.3f, v_ref: %3.3f "
820+
"feedback_ctrl_cmd.ac: %3.3f",
821+
raw_ctrl_cmd.vel, raw_ctrl_cmd.acc, control_data.dt, control_data.current_motion.vel,
822+
control_data.interpolated_traj.points.at(control_data.target_idx)
823+
.longitudinal_velocity_mps,
824+
raw_ctrl_cmd.acc);
825+
} else if (m_control_state == ControlState::STOPPING) {
826+
raw_ctrl_cmd.acc = m_smooth_stop.calculate(
827+
control_data.stop_dist, control_data.current_motion.vel, control_data.current_motion.acc,
828+
m_vel_hist, m_delay_compensation_time);
829+
raw_ctrl_cmd.vel = m_stopped_state_params.vel;
830+
831+
RCLCPP_DEBUG(
832+
logger_, "[smooth stop]: Smooth stopping. vel: %3.3f, acc: %3.3f", raw_ctrl_cmd.vel,
833+
raw_ctrl_cmd.acc);
834+
}
835+
raw_ctrl_cmd.acc = std::clamp(raw_ctrl_cmd.acc, m_min_acc, m_max_acc);
836+
m_debug_values.setValues(DebugValues::TYPE::ACC_CMD_ACC_LIMITED, raw_ctrl_cmd.acc);
837+
raw_ctrl_cmd.acc = longitudinal_utils::applyDiffLimitFilter(
838+
raw_ctrl_cmd.acc, m_prev_raw_ctrl_cmd.acc, control_data.dt, m_max_jerk, m_min_jerk);
839+
m_debug_values.setValues(DebugValues::TYPE::ACC_CMD_JERK_LIMITED, raw_ctrl_cmd.acc);
840+
}
841+
842+
// store acceleration without slope compensation
843+
m_prev_raw_ctrl_cmd = raw_ctrl_cmd;
815844

816-
RCLCPP_DEBUG(logger_, "[Stopped]. vel: %3.3f, acc: %3.3f", raw_ctrl_cmd.vel, raw_ctrl_cmd.acc);
817-
} else if (m_control_state == ControlState::EMERGENCY) {
818-
raw_ctrl_cmd = calcEmergencyCtrlCmd(control_data.dt);
845+
ctrl_cmd_as_pedal_pos.acc =
846+
applySlopeCompensation(raw_ctrl_cmd.acc, control_data.slope_angle, control_data.shift);
847+
m_debug_values.setValues(DebugValues::TYPE::ACC_CMD_SLOPE_APPLIED, ctrl_cmd_as_pedal_pos.acc);
848+
ctrl_cmd_as_pedal_pos.vel = raw_ctrl_cmd.vel;
819849
}
820850

821-
// store acceleration without slope compensation
822-
m_prev_raw_ctrl_cmd = raw_ctrl_cmd;
851+
storeAccelCmd(m_prev_raw_ctrl_cmd.acc);
823852

824-
// apply slope compensation and filter acceleration and jerk
825-
const double filtered_acc_cmd = calcFilteredAcc(raw_ctrl_cmd.acc, control_data);
826-
const Motion filtered_ctrl_cmd{raw_ctrl_cmd.vel, filtered_acc_cmd};
853+
ctrl_cmd_as_pedal_pos.acc = longitudinal_utils::applyDiffLimitFilter(
854+
ctrl_cmd_as_pedal_pos.acc, m_prev_ctrl_cmd.acc, control_data.dt, m_max_acc_cmd_diff);
827855

828856
// update debug visualization
829857
updateDebugVelAcc(control_data);
830858

831-
return filtered_ctrl_cmd;
859+
RCLCPP_DEBUG(
860+
logger_, "[final output]: acc: %3.3f, v_curr: %3.3f", ctrl_cmd_as_pedal_pos.acc,
861+
control_data.current_motion.vel);
862+
863+
return ctrl_cmd_as_pedal_pos;
832864
}
833865

834866
// Do not use nearest_idx here
@@ -912,28 +944,6 @@ enum PidLongitudinalController::Shift PidLongitudinalController::getCurrentShift
912944
return m_prev_shift;
913945
}
914946

915-
double PidLongitudinalController::calcFilteredAcc(
916-
const double raw_acc, const ControlData & control_data)
917-
{
918-
const double acc_max_filtered = std::clamp(raw_acc, m_min_acc, m_max_acc);
919-
m_debug_values.setValues(DebugValues::TYPE::ACC_CMD_ACC_LIMITED, acc_max_filtered);
920-
921-
// store ctrl cmd without slope filter
922-
storeAccelCmd(acc_max_filtered);
923-
924-
// apply slope compensation
925-
const double acc_slope_filtered =
926-
applySlopeCompensation(acc_max_filtered, control_data.slope_angle, control_data.shift);
927-
m_debug_values.setValues(DebugValues::TYPE::ACC_CMD_SLOPE_APPLIED, acc_slope_filtered);
928-
929-
// This jerk filter must be applied after slope compensation
930-
const double acc_jerk_filtered = longitudinal_utils::applyDiffLimitFilter(
931-
acc_slope_filtered, m_prev_ctrl_cmd.acc, control_data.dt, m_max_jerk, m_min_jerk);
932-
m_debug_values.setValues(DebugValues::TYPE::ACC_CMD_JERK_LIMITED, acc_jerk_filtered);
933-
934-
return acc_jerk_filtered;
935-
}
936-
937947
void PidLongitudinalController::storeAccelCmd(const double accel)
938948
{
939949
if (m_control_state == ControlState::DRIVE) {

control/autoware_trajectory_follower_node/param/longitudinal/pid.param.yaml

+3-3
Original file line numberDiff line numberDiff line change
@@ -53,12 +53,11 @@
5353

5454
# stopped state
5555
stopped_vel: 0.0
56-
stopped_acc: -3.4
57-
stopped_jerk: -5.0
56+
stopped_acc: -3.4 # denotes pedal position
5857

5958
# emergency state
6059
emergency_vel: 0.0
61-
emergency_acc: -5.0
60+
emergency_acc: -5.0 # denotes acceleration
6261
emergency_jerk: -3.0
6362

6463
# acceleration limit
@@ -68,6 +67,7 @@
6867
# jerk limit
6968
max_jerk: 2.0
7069
min_jerk: -5.0
70+
max_acc_cmd_diff: 50.0 # [m/s^2 * s^-1]
7171

7272
# slope compensation
7373
lpf_pitch_gain: 0.95

control/autoware_vehicle_cmd_gate/README.md

+4
Original file line numberDiff line numberDiff line change
@@ -78,6 +78,10 @@ The limitation values are calculated based on the 1D interpolation of the limita
7878

7979
Notation: this filter is not designed to enhance ride comfort. Its main purpose is to detect and remove abnormal values in the control outputs during the final stages of Autoware. If this filter is frequently active, it implies the control module may need tuning. If you're aiming to smoothen the signal via a low-pass filter or similar techniques, that should be handled in the control module. When the filter is activated, the topic `~/is_filter_activated` is published.
8080

81+
Notation 2: If you use vehicles in which the driving force is controlled by the accelerator/brake pedal, the jerk limit, denoting the pedal rate limit, must be sufficiently relaxed at low speeds.
82+
Otherwise, quick pedal changes at start/stop will not be possible, resulting in slow starts and creep down on hills.
83+
This functionality for starting/stopping was embedded in the source code but was removed because it was complex and could be achieved by parameters.
84+
8185
## Assumptions / Known limits
8286

8387
The parameter `check_external_emergency_heartbeat` (true by default) enables an emergency stop request from external modules.

control/autoware_vehicle_cmd_gate/config/vehicle_cmd_gate.param.yaml

+8-8
Original file line numberDiff line numberDiff line change
@@ -16,14 +16,14 @@
1616
stop_check_duration: 1.0
1717
nominal:
1818
vel_lim: 25.0
19-
reference_speed_points: [20.0, 30.0]
20-
steer_lim: [1.0, 0.8]
21-
steer_rate_lim: [1.0, 0.8]
22-
lon_acc_lim: [5.0, 4.0]
23-
lon_jerk_lim: [5.0, 4.0]
24-
lat_acc_lim: [5.0, 4.0]
25-
lat_jerk_lim: [7.0, 6.0]
26-
actual_steer_diff_lim: [1.0, 0.8]
19+
reference_speed_points: [0.1, 0.3, 20.0, 30.0]
20+
steer_lim: [1.0, 1.0, 1.0, 0.8]
21+
steer_rate_lim: [1.0, 1.0, 1.0, 0.8]
22+
lon_acc_lim: [5.0, 5.0, 5.0, 4.0]
23+
lon_jerk_lim: [80.0, 5.0, 5.0, 4.0] # The first element is required for quick pedal changes when stopping and starting.
24+
lat_acc_lim: [5.0, 5.0, 5.0, 4.0]
25+
lat_jerk_lim: [7.0, 7.0, 7.0, 6.0]
26+
actual_steer_diff_lim: [1.0, 1.0, 1.0, 0.8]
2727
on_transition:
2828
vel_lim: 50.0
2929
reference_speed_points: [20.0, 30.0]

control/autoware_vehicle_cmd_gate/src/vehicle_cmd_gate.cpp

-18
Original file line numberDiff line numberDiff line change
@@ -607,7 +607,6 @@ Control VehicleCmdGate::filterControlCommand(const Control & in)
607607
const auto mode = current_operation_mode_;
608608
const auto current_status_cmd = getActualStatusAsCommand();
609609
const auto ego_is_stopped = vehicle_stop_checker_->isVehicleStopped(stop_check_duration_);
610-
const auto input_cmd_is_stopping = in.longitudinal.acceleration < 0.0;
611610

612611
filter_.setCurrentSpeed(current_kinematics_.twist.twist.linear.x);
613612
filter_on_transition_.setCurrentSpeed(current_kinematics_.twist.twist.linear.x);
@@ -618,23 +617,6 @@ Control VehicleCmdGate::filterControlCommand(const Control & in)
618617
if (mode.is_in_transition) {
619618
filter_on_transition_.filterAll(dt, current_steer_, out, is_filter_activated);
620619
} else {
621-
// When ego is stopped and the input command is not stopping,
622-
// use the higher of actual vehicle longitudinal state
623-
// and previous longitudinal command for the filtering
624-
// this is to prevent the jerk limits being applied and causing
625-
// a delay when restarting the vehicle.
626-
627-
if (ego_is_stopped && !input_cmd_is_stopping) {
628-
auto prev_cmd = filter_.getPrevCmd();
629-
prev_cmd.longitudinal.acceleration =
630-
std::max(prev_cmd.longitudinal.acceleration, current_status_cmd.longitudinal.acceleration);
631-
// consider reverse driving
632-
prev_cmd.longitudinal.velocity = std::fabs(prev_cmd.longitudinal.velocity) >
633-
std::fabs(current_status_cmd.longitudinal.velocity)
634-
? prev_cmd.longitudinal.velocity
635-
: current_status_cmd.longitudinal.velocity;
636-
filter_.setPrevCmd(prev_cmd);
637-
}
638620
filter_.filterAll(dt, current_steer_, out, is_filter_activated);
639621
}
640622

0 commit comments

Comments
 (0)