Skip to content

Commit 4e1a86a

Browse files
committed
not sure stopped
1 parent 7398f36 commit 4e1a86a

File tree

1 file changed

+11
-9
lines changed

1 file changed

+11
-9
lines changed

control/pid_longitudinal_controller/src/pid_longitudinal_controller.cpp

+11-9
Original file line numberDiff line numberDiff line change
@@ -518,10 +518,12 @@ PidLongitudinalController::Motion PidLongitudinalController::calcEmergencyCtrlCm
518518

519519
void PidLongitudinalController::updateControlState(const ControlData & control_data)
520520
{
521-
const double target_vel =
522-
control_data.interpolated_traj.points.at(control_data.target_idx).longitudinal_velocity_mps;
523-
const double target_acc =
524-
control_data.interpolated_traj.points.at(control_data.target_idx).acceleration_mps2;
521+
// const double target_vel =
522+
// control_data.interpolated_traj.points.at(control_data.target_idx).longitudinal_velocity_mps;
523+
// const double target_acc =
524+
// control_data.interpolated_traj.points.at(control_data.target_idx).acceleration_mps2;
525+
const double vel_after_delay = control_data.state_after_delay.vel;
526+
const double acc_after_delay = control_data.state_after_delay.acc;
525527
const double stop_dist = control_data.stop_dist;
526528

527529
// flags for state transition
@@ -536,8 +538,8 @@ void PidLongitudinalController::updateControlState(const ControlData & control_d
536538

537539
const bool stopping_condition = stop_dist < p.stopping_state_stop_dist;
538540
if (
539-
std::fabs(target_vel) > p.stopped_state_entry_vel ||
540-
std::fabs(target_acc) > p.stopped_state_entry_acc) {
541+
std::fabs(vel_after_delay) > p.stopped_state_entry_vel ||
542+
std::fabs(acc_after_delay) > p.stopped_state_entry_acc) {
541543
m_last_running_time = std::make_shared<rclcpp::Time>(node_->now());
542544
}
543545
const bool stopped_condition =
@@ -582,7 +584,7 @@ void PidLongitudinalController::updateControlState(const ControlData & control_d
582584

583585
if (m_enable_smooth_stop) {
584586
if (stopping_condition) {
585-
m_smooth_stop.init(control_data.state_after_delay.vel, control_data.stop_dist);
587+
m_smooth_stop.init(vel_after_delay, control_data.stop_dist);
586588
return changeState(ControlState::STOPPING);
587589
}
588590
} else {
@@ -673,8 +675,8 @@ PidLongitudinalController::Motion PidLongitudinalController::calcCtrlCmd(
673675
target_motion.vel, raw_ctrl_cmd.acc);
674676
} else if (m_control_state == ControlState::STOPPING) {
675677
raw_ctrl_cmd.acc = m_smooth_stop.calculate(
676-
control_data.stop_dist, control_data.current_motion.vel, control_data.current_motion.acc,
677-
m_vel_hist, m_delay_compensation_time);
678+
control_data.stop_dist, control_data.state_after_delay.vel,
679+
control_data.state_after_delay.acc, m_vel_hist, m_delay_compensation_time);
678680
raw_ctrl_cmd.vel = m_stopped_state_params.vel;
679681

680682
RCLCPP_DEBUG(

0 commit comments

Comments
 (0)