@@ -150,9 +150,8 @@ PidLongitudinalController::PidLongitudinalController(rclcpp::Node & node)
150
150
// parameters for stop state
151
151
{
152
152
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]
156
155
}
157
156
158
157
// parameters for emergency state
@@ -168,8 +167,9 @@ PidLongitudinalController::PidLongitudinalController(rclcpp::Node & node)
168
167
m_min_acc = node.declare_parameter <double >(" min_acc" ); // [m/s^2]
169
168
170
169
// 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]
173
173
174
174
// parameters for slope compensation
175
175
m_adaptive_trajectory_velocity_th =
@@ -353,7 +353,6 @@ rcl_interfaces::msg::SetParametersResult PidLongitudinalController::paramCallbac
353
353
auto & p = m_stopped_state_params;
354
354
update_param (" stopped_vel" , p.vel );
355
355
update_param (" stopped_acc" , p.acc );
356
- update_param (" stopped_jerk" , p.jerk );
357
356
}
358
357
359
358
// emergency state
@@ -370,6 +369,7 @@ rcl_interfaces::msg::SetParametersResult PidLongitudinalController::paramCallbac
370
369
// jerk limit
371
370
update_param (" max_jerk" , m_max_jerk);
372
371
update_param (" min_jerk" , m_min_jerk);
372
+ update_param (" max_acc_cmd_diff" , m_max_acc_cmd_diff);
373
373
374
374
// slope compensation
375
375
update_param (" max_pitch_rad" , m_max_pitch_rad);
@@ -565,26 +565,30 @@ PidLongitudinalController::ControlData PidLongitudinalController::getControlData
565
565
return control_data;
566
566
}
567
567
568
- PidLongitudinalController::Motion PidLongitudinalController::calcEmergencyCtrlCmd (
569
- const double dt) const
568
+ PidLongitudinalController::Motion PidLongitudinalController::calcEmergencyCtrlCmd (const double dt)
570
569
{
571
570
// These accelerations are without slope compensation
572
571
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 );
577
581
578
582
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 );
580
585
581
- return Motion{vel, acc} ;
586
+ return raw_ctrl_cmd ;
582
587
}
583
588
584
589
void PidLongitudinalController::updateControlState (const ControlData & control_data)
585
590
{
586
591
const double current_vel = control_data.current_motion .vel ;
587
- const double current_acc = control_data.current_motion .acc ;
588
592
const double stop_dist = control_data.stop_dist ;
589
593
590
594
// flags for state transition
@@ -599,8 +603,8 @@ void PidLongitudinalController::updateControlState(const ControlData & control_d
599
603
600
604
const bool stopping_condition = stop_dist < p.stopping_state_stop_dist ;
601
605
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
+
604
608
// Case where the ego slips in the opposite direction of the gear due to e.g. a slope is also
605
609
// considered as a stop
606
610
const bool is_not_running = [&]() {
@@ -701,7 +705,7 @@ void PidLongitudinalController::updateControlState(const ControlData & control_d
701
705
m_pid_vel.reset ();
702
706
m_lpf_vel_error->reset (0.0 );
703
707
// 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 );
705
709
return changeState (ControlState::DRIVE);
706
710
}
707
711
return ;
@@ -747,8 +751,6 @@ void PidLongitudinalController::updateControlState(const ControlData & control_d
747
751
748
752
m_pid_vel.reset ();
749
753
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 );
752
754
return changeState (ControlState::DRIVE);
753
755
}
754
756
@@ -780,55 +782,85 @@ PidLongitudinalController::Motion PidLongitudinalController::calcCtrlCmd(
780
782
const size_t target_idx = control_data.target_idx ;
781
783
782
784
// velocity and acceleration command
783
- Motion raw_ctrl_cmd {
785
+ Motion ctrl_cmd_as_pedal_pos {
784
786
control_data.interpolated_traj .points .at (target_idx).longitudinal_velocity_mps ,
785
787
control_data.interpolated_traj .points .at (target_idx).acceleration_mps2 };
786
788
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 ;
792
793
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 );
805
800
806
801
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;
815
844
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 ;
819
849
}
820
850
821
- // store acceleration without slope compensation
822
- m_prev_raw_ctrl_cmd = raw_ctrl_cmd;
851
+ storeAccelCmd (m_prev_raw_ctrl_cmd.acc );
823
852
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);
827
855
828
856
// update debug visualization
829
857
updateDebugVelAcc (control_data);
830
858
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;
832
864
}
833
865
834
866
// Do not use nearest_idx here
@@ -912,28 +944,6 @@ enum PidLongitudinalController::Shift PidLongitudinalController::getCurrentShift
912
944
return m_prev_shift;
913
945
}
914
946
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
-
937
947
void PidLongitudinalController::storeAccelCmd (const double accel)
938
948
{
939
949
if (m_control_state == ControlState::DRIVE) {
0 commit comments