No version for distro humble. Known supported distros are highlighted in the buttons above.
No version for distro jazzy. Known supported distros are highlighted in the buttons above.
No version for distro rolling. Known supported distros are highlighted in the buttons above.

autoware_pid_longitudinal_controller package from autoware_universe repo

autoware_adapi_specs autoware_agnocast_wrapper autoware_auto_common autoware_component_interface_specs_universe autoware_component_interface_tools autoware_component_interface_utils autoware_cuda_dependency_meta autoware_fake_test_node autoware_glog_component autoware_goal_distance_calculator autoware_grid_map_utils autoware_path_distance_calculator autoware_polar_grid autoware_time_utils autoware_traffic_light_recognition_marker_publisher autoware_traffic_light_utils autoware_universe_utils tier4_api_utils autoware_autonomous_emergency_braking autoware_collision_detector autoware_control_performance_analysis autoware_control_validator autoware_external_cmd_selector autoware_joy_controller autoware_lane_departure_checker autoware_mpc_lateral_controller autoware_obstacle_collision_checker autoware_operation_mode_transition_manager autoware_pid_longitudinal_controller autoware_predicted_path_checker autoware_pure_pursuit autoware_shift_decider autoware_smart_mpc_trajectory_follower autoware_trajectory_follower_base autoware_trajectory_follower_node autoware_vehicle_cmd_gate autoware_control_evaluator autoware_kinematic_evaluator autoware_localization_evaluator autoware_perception_online_evaluator autoware_planning_evaluator autoware_scenario_simulator_v2_adapter tier4_autoware_api_launch tier4_control_launch tier4_localization_launch tier4_map_launch tier4_perception_launch tier4_planning_launch tier4_sensing_launch tier4_simulator_launch tier4_system_launch tier4_vehicle_launch autoware_geo_pose_projector autoware_gyro_odometer autoware_ar_tag_based_localizer autoware_landmark_manager autoware_lidar_marker_localizer autoware_localization_error_monitor autoware_ndt_scan_matcher autoware_pose2twist autoware_pose_covariance_modifier autoware_pose_estimator_arbiter autoware_pose_initializer autoware_pose_instability_detector yabloc_common yabloc_image_processing yabloc_monitor yabloc_particle_filter yabloc_pose_initializer autoware_lanelet2_map_visualizer autoware_map_height_fitter autoware_map_tf_generator autoware_bytetrack autoware_cluster_merger autoware_compare_map_segmentation autoware_crosswalk_traffic_light_estimator autoware_detected_object_feature_remover autoware_detected_object_validation autoware_detection_by_tracker autoware_elevation_map_loader autoware_euclidean_cluster autoware_ground_segmentation autoware_image_projection_based_fusion autoware_lidar_apollo_instance_segmentation autoware_lidar_centerpoint autoware_lidar_transfusion autoware_map_based_prediction autoware_multi_object_tracker autoware_object_merger autoware_object_range_splitter autoware_object_velocity_splitter autoware_occupancy_grid_map_outlier_filter autoware_probabilistic_occupancy_grid_map autoware_radar_crossing_objects_noise_filter autoware_radar_fusion_to_detected_object autoware_radar_object_clustering autoware_radar_object_tracker autoware_radar_tracks_msgs_converter autoware_raindrop_cluster_filter autoware_shape_estimation autoware_simple_object_merger autoware_tensorrt_classifier autoware_tensorrt_common autoware_tensorrt_yolox autoware_tracking_object_merger autoware_traffic_light_arbiter autoware_traffic_light_category_merger autoware_traffic_light_classifier autoware_traffic_light_fine_detector autoware_traffic_light_map_based_detector autoware_traffic_light_multi_camera_fusion autoware_traffic_light_occlusion_predictor autoware_traffic_light_selector autoware_traffic_light_visualization perception_utils autoware_costmap_generator autoware_external_velocity_limit_selector autoware_freespace_planner autoware_freespace_planning_algorithms autoware_mission_planner_universe autoware_obstacle_cruise_planner autoware_obstacle_stop_planner autoware_path_optimizer autoware_path_smoother autoware_planning_validator autoware_remaining_distance_time_calculator autoware_rtc_interface autoware_scenario_selector autoware_surround_obstacle_checker autoware_behavior_path_avoidance_by_lane_change_module autoware_behavior_path_dynamic_obstacle_avoidance_module autoware_behavior_path_external_request_lane_change_module autoware_behavior_path_goal_planner_module autoware_behavior_path_lane_change_module autoware_behavior_path_planner autoware_behavior_path_planner_common autoware_behavior_path_sampling_planner_module autoware_behavior_path_side_shift_module autoware_behavior_path_start_planner_module autoware_behavior_path_static_obstacle_avoidance_module autoware_behavior_velocity_blind_spot_module autoware_behavior_velocity_crosswalk_module autoware_behavior_velocity_detection_area_module autoware_behavior_velocity_intersection_module autoware_behavior_velocity_no_drivable_lane_module autoware_behavior_velocity_no_stopping_area_module autoware_behavior_velocity_occlusion_spot_module autoware_behavior_velocity_rtc_interface autoware_behavior_velocity_run_out_module autoware_behavior_velocity_speed_bump_module autoware_behavior_velocity_template_module autoware_behavior_velocity_traffic_light_module autoware_behavior_velocity_virtual_traffic_light_module autoware_behavior_velocity_walkway_module autoware_motion_velocity_dynamic_obstacle_stop_module autoware_motion_velocity_obstacle_cruise_module autoware_motion_velocity_obstacle_slow_down_module autoware_motion_velocity_obstacle_velocity_limiter_module autoware_motion_velocity_out_of_lane_module autoware_bezier_sampler autoware_frenet_planner autoware_path_sampler autoware_sampler_common autoware_cuda_pointcloud_preprocessor autoware_cuda_utils autoware_image_diagnostics autoware_image_transport_decompressor autoware_imu_corrector autoware_pcl_extensions autoware_pointcloud_preprocessor autoware_radar_scan_to_pointcloud2 autoware_radar_static_pointcloud_filter autoware_radar_threshold_filter autoware_radar_tracks_noise_filter autoware_livox_tag_filter autoware_carla_interface autoware_dummy_perception_publisher autoware_fault_injection autoware_learning_based_vehicle_model autoware_simple_planning_simulator autoware_vehicle_door_simulator tier4_dummy_object_rviz_plugin autoware_bluetooth_monitor autoware_component_monitor autoware_component_state_monitor autoware_default_adapi autoware_adapi_adaptors autoware_adapi_visualizers autoware_automatic_pose_initializer autoware_diagnostic_graph_aggregator autoware_diagnostic_graph_utils autoware_dummy_diag_publisher autoware_dummy_infrastructure autoware_duplicated_node_checker autoware_hazard_status_converter autoware_mrm_comfortable_stop_operator autoware_mrm_emergency_stop_operator autoware_mrm_handler autoware_processing_time_checker autoware_system_diagnostic_monitor autoware_system_monitor autoware_topic_relay_controller autoware_topic_state_monitor autoware_velodyne_monitor reaction_analyzer autoware_accel_brake_map_calibrator autoware_external_cmd_converter autoware_raw_vehicle_cmd_converter autoware_steer_offset_estimator autoware_bag_time_manager_rviz_plugin autoware_mission_details_overlay_rviz_plugin autoware_overlay_rviz_plugin autoware_string_stamped_rviz_plugin autoware_perception_rviz_plugin tier4_adapi_rviz_plugin tier4_camera_view_rviz_plugin tier4_datetime_rviz_plugin tier4_localization_rviz_plugin tier4_planning_factor_rviz_plugin tier4_planning_rviz_plugin tier4_state_rviz_plugin tier4_system_rviz_plugin tier4_traffic_light_rviz_plugin tier4_vehicle_rviz_plugin

Package Summary

Tags No category tags.
Version 0.43.0
License Apache 2.0
Build type AMENT_CMAKE
Use RECOMMENDED

Repository Summary

Checkout URI https://github.com/autowarefoundation/autoware_universe.git
VCS Type git
VCS Version main
Last Updated 2025-04-04
Dev Status UNMAINTAINED
CI status No Continuous Integration
Released UNRELEASED
Tags No category tags.
Contributing Help Wanted (0)
Good First Issues (0)
Pull Requests to Review (0)

Package Description

PID-based longitudinal controller

Additional Links

No additional links.

Maintainers

  • Takamasa Horibe
  • Takayuki Murooka
  • Mamoru Sobue
  • Yuki Takagi

Authors

  • Takamasa Horibe
  • Maxime CLEMENT
  • Takayuki Murooka

PID Longitudinal Controller

Purpose / Use cases

The longitudinal_controller computes the target acceleration to achieve the target velocity set at each point of the target trajectory using a feed-forward/back control.

It also contains a slope force correction that takes into account road slope information, and a delay compensation function. It is assumed that the target acceleration calculated here will be properly realized by the vehicle interface.

Note that the use of this module is not mandatory for Autoware if the vehicle supports the “target speed” interface.

Design / Inner-workings / Algorithms

States

This module has four state transitions as shown below in order to handle special processing in a specific situation.

  • DRIVE
    • Executes target velocity tracking by PID control.
    • It also applies the delay compensation and slope compensation.
  • STOPPING
    • Controls the motion just before stopping.
    • Special sequence is performed to achieve accurate and smooth stopping.
  • STOPPED
    • Performs operations in the stopped state (e.g. brake hold)
  • EMERGENCY.
    • Enters an emergency state when certain conditions are met (e.g., when the vehicle has crossed a certain distance of a stop line).
    • The recovery condition (whether or not to keep emergency state until the vehicle completely stops) or the deceleration in the emergency state are defined by parameters.

The state transition diagram is shown below.

LongitudinalControllerStateTransition

Logics

Control Block Diagram

LongitudinalControllerDiagram

FeedForward (FF)

The reference acceleration set in the trajectory and slope compensation terms are output as a feedforward. Under ideal conditions with no modeling error, this FF term alone should be sufficient for velocity tracking.

Tracking errors causing modeling or discretization errors are removed by the feedback control (now using PID).

Brake keeping

From the viewpoint of ride comfort, stopping with 0 acceleration is important because it reduces the impact of braking. However, if the target acceleration when stopping is 0, the vehicle may cross over the stop line or accelerate a little in front of the stop line due to vehicle model error or gradient estimation error.

For reliable stopping, the target acceleration calculated by the FeedForward system is limited to a negative acceleration when stopping.

BrakeKeepingDiagram

Slope compensation

Based on the slope information, a compensation term is added to the target acceleration.

There are two sources of the slope information, which can be switched by a parameter.

  • Pitch of the estimated ego-pose (default)
    • Calculates the current slope from the pitch angle of the estimated ego-pose
    • Pros: Easily available
    • Cons: Cannot extract accurate slope information due to the influence of vehicle vibration.
  • Z coordinate on the trajectory
    • Calculates the road slope from the difference of z-coordinates between the front and rear wheel positions in the target trajectory
    • Pros: More accurate than pitch information, if the z-coordinates of the route are properly maintained
    • Pros: Can be used in combination with delay compensation (not yet implemented)
    • Cons: z-coordinates of high-precision map is needed.
    • Cons: Does not support free space planning (for now)

We also offer the options to switch between these, depending on driving conditions.

Notation: This function works correctly only in a vehicle system that does not have acceleration feedback in the low-level control system.

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. For instance, if the vehicle is attempting to start with an acceleration of 1.0 m/s^2 and a gravity correction of -1.0 m/s^2 is applied, the output value will be 0. If this output value is mistakenly treated as the target acceleration, the vehicle will not start.

A suitable example of a vehicle system for the slope compensation function is one in which the output acceleration from the longitudinal_controller is converted into target accel/brake pedal input without any feedbacks. In this case, the output acceleration is just used as a feedforward term to calculate the target pedal, and hence the issue mentioned above does not arise.

Note: The angle of the slope is defined as positive for an uphill slope, while the pitch angle of the ego pose is defined as negative when facing upward. They have an opposite definition.

slope_definition

PID control

For deviations that cannot be handled by FeedForward control, such as model errors, PID control is used to construct a feedback system.

This PID control calculates the target acceleration from the deviation between the current ego-velocity and the target velocity.

This PID logic has a maximum value for the output of each term. This is to prevent the following:

  • Large integral terms may cause unintended behavior by users.
  • Unintended noise may cause the output of the derivative term to be very large.

Note: by default, the integral term in the control system is not accumulated when the vehicle is stationary. This precautionary measure aims to prevent unintended accumulation of the integral term in scenarios where Autoware assumes the vehicle is engaged, but an external system has immobilized the vehicle to initiate startup procedures.

However, certain situations may arise, such as when the vehicle encounters a depression in the road surface during startup or if the slope compensation is inaccurately estimated (lower than necessary), leading to a failure to initiate motion. To address these scenarios, it is possible to activate error integration even when the vehicle is at rest by setting the enable_integration_at_low_speed parameter to true.

When enable_integration_at_low_speed is set to true, the PID controller will initiate integration of the acceleration error after a specified duration defined by the time_threshold_before_pid_integration parameter has elapsed without the vehicle surpassing a minimum velocity set by the current_vel_threshold_pid_integration parameter.

The presence of the time_threshold_before_pid_integration parameter is important for practical PID tuning. Integrating the error when the vehicle is stationary or at low speed can complicate PID tuning. This parameter effectively introduces a delay before the integral part becomes active, preventing it from kicking in immediately. This delay allows for more controlled and effective tuning of the PID controller.

At present, PID control is implemented from the viewpoint of trade-off between development/maintenance cost and performance. This may be replaced by a higher performance controller (adaptive control or robust control) in future development.

Time delay compensation

At high speeds, the delay of actuator systems such as gas pedals and brakes has a significant impact on driving accuracy. Depending on the actuating principle of the vehicle, the mechanism that physically controls the gas pedal and brake typically has a delay of about a hundred millisecond.

In this controller, the predicted ego-velocity and the target velocity after the delay time are calculated and used for the feedback to address the time delay problem.

Slope compensation

Based on the slope information, a compensation term is added to the target acceleration.

There are two sources of the slope information, which can be switched by a parameter.

  • Pitch of the estimated ego-pose (default)
    • Calculates the current slope from the pitch angle of the estimated ego-pose
    • Pros: Easily available
    • Cons: Cannot extract accurate slope information due to the influence of vehicle vibration.
  • Z coordinate on the trajectory
    • Calculates the road slope from the difference of z-coordinates between the front and rear wheel positions in the target trajectory
    • Pros: More accurate than pitch information, if the z-coordinates of the route are properly maintained
    • Pros: Can be used in combination with delay compensation (not yet implemented)
    • Cons: z-coordinates of high-precision map is needed.
    • Cons: Does not support free space planning (for now)

Assumptions / Known limits

  1. Smoothed target velocity and its acceleration shall be set in the trajectory
    1. The velocity command is not smoothed inside the controller (only noise may be removed).
    2. For step-like target signal, tracking is performed as fast as possible.
  2. The vehicle velocity must be an appropriate value
    1. The ego-velocity must be a signed-value corresponding to the forward/backward direction
    2. The ego-velocity should be given with appropriate noise processing.
    3. If there is a large amount of noise in the ego-velocity, the tracking performance will be significantly reduced.
  3. The output of this controller must be achieved by later modules (e.g. vehicle interface).
    1. If the vehicle interface does not have the target velocity or acceleration interface (e.g., the vehicle only has a gas pedal and brake interface), an appropriate conversion must be done after this controller.

Inputs / Outputs / API

Input

Set the following from the controller_node

  • autoware_planning_msgs/Trajectory : reference trajectory to follow.
  • nav_msgs/Odometry: current odometry

Output

Return LongitudinalOutput which contains the following to the controller node

  • autoware_control_msgs/Longitudinal: command to control the longitudinal motion of the vehicle. It contains the target velocity and target acceleration.
  • LongitudinalSyncData
    • velocity convergence(currently not used)

PIDController class

The PIDController class is straightforward to use. First, gains and limits must be set (using setGains() and setLimits()) for the proportional (P), integral (I), and derivative (D) components. Then, the velocity can be calculated by providing the current error and time step duration to the calculate() function.

Parameter description

The default parameters defined in param/lateral_controller_defaults.param.yaml are adjusted to the AutonomouStuff Lexus RX 450h for under 40 km/h driving.

Name Type Description Default value
delay_compensation_time double delay for longitudinal control [s] 0.17
enable_smooth_stop bool flag to enable transition to STOPPING true
enable_overshoot_emergency bool flag to enable transition to EMERGENCY when the ego is over the stop line with a certain distance. See emergency_state_overshoot_stop_dist. true
enable_large_tracking_error_emergency bool flag to enable transition to EMERGENCY when the closest trajectory point search is failed due to a large deviation between trajectory and ego pose. true
enable_slope_compensation bool flag to modify output acceleration for slope compensation. The source of the slope angle can be selected from ego-pose or trajectory angle. See use_trajectory_for_pitch_calculation. true
enable_brake_keeping_before_stop bool flag to keep a certain acceleration during DRIVE state before the ego stops. See Brake keeping. false
enable_keep_stopped_until_steer_convergence bool flag to keep stopped condition until until the steer converges. true
max_acc double max value of output acceleration [m/s^2] 3.0
min_acc double min value of output acceleration [m/s^2] -5.0
max_jerk double max value of jerk of output acceleration [m/s^3] 2.0
min_jerk double min value of jerk of output acceleration [m/s^3] -5.0
use_trajectory_for_pitch_calculation bool If true, the slope is estimated from trajectory z-level. Otherwise the pitch angle of the ego pose is used. false
lpf_pitch_gain double gain of low-pass filter for pitch estimation 0.95
max_pitch_rad double max value of estimated pitch [rad] 0.1
min_pitch_rad double min value of estimated pitch [rad] -0.1

State transition

Name Type Description Default value
drive_state_stop_dist double The state will transit to DRIVE when the distance to the stop point is longer than drive_state_stop_dist + drive_state_offset_stop_dist [m] 0.5
drive_state_offset_stop_dist double The state will transit to DRIVE when the distance to the stop point is longer than drive_state_stop_dist + drive_state_offset_stop_dist [m] 1.0
stopping_state_stop_dist double The state will transit to STOPPING when the distance to the stop point is shorter than stopping_state_stop_dist [m] 0.5
stopped_state_entry_vel double threshold of the ego velocity in transition to the STOPPED state [m/s] 0.01
stopped_state_entry_acc double threshold of the ego acceleration in transition to the STOPPED state [m/s^2] 0.1
emergency_state_overshoot_stop_dist double If enable_overshoot_emergency is true and the ego is emergency_state_overshoot_stop_dist-meter ahead of the stop point, the state will transit to EMERGENCY. [m] 1.5

DRIVE Parameter

Name Type Description Default value
kp double p gain for longitudinal control 1.0
ki double i gain for longitudinal control 0.1
kd double d gain for longitudinal control 0.0
max_out double max value of PID’s output acceleration during DRIVE state [m/s^2] 1.0
min_out double min value of PID’s output acceleration during DRIVE state [m/s^2] -1.0
max_p_effort double max value of acceleration with p gain 1.0
min_p_effort double min value of acceleration with p gain -1.0
max_i_effort double max value of acceleration with i gain 0.3
min_i_effort double min value of acceleration with i gain -0.3
max_d_effort double max value of acceleration with d gain 0.0
min_d_effort double min value of acceleration with d gain 0.0
lpf_vel_error_gain double gain of low-pass filter for velocity error 0.9
enable_integration_at_low_speed bool Whether to enable integration of acceleration errors when the vehicle speed is lower than current_vel_threshold_pid_integration or not. false
current_vel_threshold_pid_integration double Velocity error is integrated for I-term only when the absolute value of current velocity is larger than this parameter. [m/s] 0.5
time_threshold_before_pid_integration double How much time without the vehicle moving must past to enable PID error integration. [s] 5.0
brake_keeping_acc double If enable_brake_keeping_before_stop is true, a certain acceleration is kept during DRIVE state before the ego stops [m/s^2] See Brake keeping. 0.2

STOPPING Parameter (smooth stop)

Smooth stop is enabled if enable_smooth_stop is true. In smooth stop, strong acceleration (strong_acc) will be output first to decrease the ego velocity. Then weak acceleration (weak_acc) will be output to stop smoothly by decreasing the ego jerk. If the ego does not stop in a certain time or some-meter over the stop point, weak acceleration to stop right (weak_stop_acc) now will be output. If the ego is still running, strong acceleration (strong_stop_acc) to stop right now will be output.

Name Type Description Default value
smooth_stop_max_strong_acc double max strong acceleration [m/s^2] -0.5
smooth_stop_min_strong_acc double min strong acceleration [m/s^2] -0.8
smooth_stop_weak_acc double weak acceleration [m/s^2] -0.3
smooth_stop_weak_stop_acc double weak acceleration to stop right now [m/s^2] -0.8
smooth_stop_strong_stop_acc double strong acceleration to be output when the ego is smooth_stop_strong_stop_dist-meter over the stop point. [m/s^2] -3.4
smooth_stop_max_fast_vel double max fast vel to judge the ego is running fast [m/s]. If the ego is running fast, strong acceleration will be output. 0.5
smooth_stop_min_running_vel double min ego velocity to judge if the ego is running or not [m/s] 0.01
smooth_stop_min_running_acc double min ego acceleration to judge if the ego is running or not [m/s^2] 0.01
smooth_stop_weak_stop_time double max time to output weak acceleration [s]. After this, strong acceleration will be output. 0.8
smooth_stop_weak_stop_dist double Weak acceleration will be output when the ego is smooth_stop_weak_stop_dist-meter before the stop point. [m] -0.3
smooth_stop_strong_stop_dist double Strong acceleration will be output when the ego is smooth_stop_strong_stop_dist-meter over the stop point. [m] -0.5

STOPPED Parameter

The STOPPED state assumes that the vehicle is completely stopped with the brakes fully applied. Therefore, stopped_acc should be set to a value that allows the vehicle to apply the strongest possible brake. If stopped_acc is not sufficiently low, there is a possibility of sliding down on steep slopes.

Name Type Description Default value
stopped_vel double target velocity in STOPPED state [m/s] 0.0
stopped_acc double target acceleration in STOPPED state [m/s^2] -3.4
stopped_jerk double target jerk in STOPPED state [m/s^3] -5.0

EMERGENCY Parameter

Name Type Description Default value
emergency_vel double target velocity in EMERGENCY state [m/s] 0.0
emergency_acc double target acceleration in an EMERGENCY state [m/s^2] -5.0
emergency_jerk double target jerk in an EMERGENCY state [m/s^3] -3.0

Future extensions / Unimplemented parts

CHANGELOG

Changelog for package autoware_pid_longitudinal_controller

0.43.0 (2025-03-21)

  • Merge remote-tracking branch 'origin/main' into chore/bump-version-0.43
  • chore: rename from [autoware.universe]{.title-ref} to [autoware_universe]{.title-ref} (#10306)
  • Contributors: Hayato Mizushima, Yutaka Kondo

0.42.0 (2025-03-03)

  • Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base
  • feat(autoware_utils): replace autoware_universe_utils with autoware_utils (#10191)
  • fix: add missing includes to autoware_universe_utils (#10091)
  • Contributors: Fumiya Watanabe, Ryohsuke Mitsudome, 心刚

0.41.2 (2025-02-19)

  • chore: bump version to 0.41.1 (#10088)
  • Contributors: Ryohsuke Mitsudome

0.41.1 (2025-02-10)

0.41.0 (2025-01-29)

  • Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base
  • fix: remove unnecessary parameters (#9935)
  • feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in fil… (#9848) feat: tier4_debug_msgs changed to autoware_internal_debug_msgs in files control/autoware_pid_longitudinal_controller
  • feat(pid_longitudinal_controller): add new slope compensation mode trajectory_goal_adaptive (#9705)
  • feat(pid_longitudinal_controller): add virtual wall for dry steering and emergency (#9685)
    • feat(pid_longitudinal_controller): add virtual wall for dry steering and emergency

    * fix

  • feat(pid_longitudinal_controller): remove trans/rot deviation validation since the control_validator has the same feature (#9675)
    • feat(pid_longitudinal_controller): remove trans/rot deviation validation since the control_validator has the same feature

    * fix test ---------

  • feat(pid_longitudinal_controller): add smooth_stop mode in debug_values (#9681)
  • feat(pid_longitudinal_controller): update trajectory_adaptive; add debug_values, adopt rate limit fillter (#9656)
  • fix(autoware_pid_longitudinal_controller): fix bugprone-branch-clone (#9629) fix: bugprone-branch-clone
  • Contributors: Fumiya Watanabe, Takayuki Murooka, Vishal Chauhan, Yuki TAKAGI, kobayu858

0.40.0 (2024-12-12)

  • Merge branch 'main' into release-0.40.0
  • Revert "chore(package.xml): bump version to 0.39.0 (#9587)" This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5.
  • fix: fix ticket links in CHANGELOG.rst (#9588)
  • chore(package.xml): bump version to 0.39.0 (#9587)
    • chore(package.xml): bump version to 0.39.0
    • fix: fix ticket links in CHANGELOG.rst

    * fix: remove unnecessary diff ---------Co-authored-by: Yutaka Kondo <<yutaka.kondo@youtalk.jp>>

  • fix: fix ticket links in CHANGELOG.rst (#9588)
  • fix(cpplint): include what you use - control (#9565)
  • 0.39.0
  • update changelog
  • fix: fix ticket links to point to https://github.com/autowarefoundation/autoware_universe (#9304)
  • feat(pid_longitudinal_controller): suppress rclcpp_warning/error (#9384)
    • feat(pid_longitudinal_controller): suppress rclcpp_warning/error

    * update codeowner ---------

  • feat(trajectory_follower): publsih control horzion (#8977)
    • feat(trajectory_follower): publsih control horzion
    • fix typo
    • rename functions and minor refactor
    • add option to enable horizon pub
    • add tests for horizon
    • update docs

    * rename to ~/debug/control_cmd_horizon ---------

  • fix: fix ticket links to point to https://github.com/autowarefoundation/autoware_universe (#9304)
  • chore(package.xml): bump version to 0.38.0 (#9266) (#9284)
    • unify package.xml version to 0.37.0
    • remove system_monitor/CHANGELOG.rst
    • add changelog

    * 0.38.0

  • Contributors: Esteve Fernandez, Fumiya Watanabe, Kosuke Takeuchi, M. Fatih Cırıt, Ryohsuke Mitsudome, Takayuki Murooka, Yutaka Kondo

0.39.0 (2024-11-25)

0.38.0 (2024-11-08)

  • unify package.xml version to 0.37.0
  • refactor(autoware_interpolation): prefix package and namespace with autoware (#8088) Co-authored-by: kosuke55 <<kosuke.tnp@gmail.com>>
  • fix(pid_longitudinal_controller): fix the same point error (#8758)
    • fix same point
  • feat(pid_longitudinal_controller)!: add acceleration feedback block (#8325)
  • refactor(control/pid_longitudinal_controller): rework parameters (#6707)
    • reset and re-apply refactoring
    • style(pre-commit): autofix
    • .

    * .

    Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com>

  • feat(pid_longitudinal_controller): re-organize diff limit structure and fix state change condition (#7718) change diff limit structure change stopped condition define a new param
  • fix(controller): revival of dry steering (#7903) * Revert "fix(autoware_mpc_lateral_controller): delete the zero speed constraint (#7673)" This reverts commit 69258bd92cb8a0ff8320df9b2302db72975e027f.
    • dry steering
    • add comments

    * add minor fix and modify unit test for dry steering ---------

  • fix(autoware_pid_longitudinal_controller, autoware_trajectory_follower_node): unite diagnostic_updater_ in PID and MPC. (#7674)
    • diag_updater_ added in PID
    • correct the pointer form

    * pre-commit ---------

  • refactor(universe_utils/motion_utils)!: add autoware namespace (#7594)
  • refactor(motion_utils)!: add autoware prefix and include dir (#7539) refactor(motion_utils): add autoware prefix and include dir
  • feat(autoware_universe_utils)!: rename from tier4_autoware_utils (#7538) Co-authored-by: kosuke55 <<kosuke.tnp@gmail.com>>
  • refactor(control)!: refactor directory structures of the trajectory followers (#7521)
    • control_traj
    • add follower_node

    * fix

  • ci(pre-commit): autoupdate (#7499) Co-authored-by: M. Fatih Cırıt <<mfc@leodrive.ai>>
  • refactor(trajectory_follower_node): trajectory follower node add autoware prefix (#7344)
    • rename trajectory follower node package
    • update dependencies, launch files, and README files
    • fix formats

    * remove autoware_ prefix from launch arg option ---------

  • refactor(trajectory_follower_base): trajectory follower base add autoware prefix (#7343)
    • rename trajectory follower base package
    • update dependencies and includes

    * fix formats ---------

  • refactor(vehicle_info_utils)!: prefix package and namespace with autoware (#7353)
    • chore(autoware_vehicle_info_utils): rename header
    • chore(bpp-common): vehicle info
    • chore(path_optimizer): vehicle info
    • chore(velocity_smoother): vehicle info
    • chore(bvp-common): vehicle info
    • chore(static_centerline_generator): vehicle info
    • chore(obstacle_cruise_planner): vehicle info
    • chore(obstacle_velocity_limiter): vehicle info
    • chore(mission_planner): vehicle info
    • chore(obstacle_stop_planner): vehicle info
    • chore(planning_validator): vehicle info
    • chore(surround_obstacle_checker): vehicle info
    • chore(goal_planner): vehicle info
    • chore(start_planner): vehicle info
    • chore(control_performance_analysis): vehicle info
    • chore(lane_departure_checker): vehicle info
    • chore(predicted_path_checker): vehicle info
    • chore(vehicle_cmd_gate): vehicle info
    • chore(obstacle_collision_checker): vehicle info
    • chore(operation_mode_transition_manager): vehicle info
    • chore(mpc): vehicle info
    • chore(control): vehicle info
    • chore(common): vehicle info
    • chore(perception): vehicle info
    • chore(evaluator): vehicle info
    • chore(freespace): vehicle info
    • chore(planning): vehicle info
    • chore(vehicle): vehicle info
    • chore(simulator): vehicle info
    • chore(launch): vehicle info
    • chore(system): vehicle info
    • chore(sensing): vehicle info

    * fix(autoware_joy_controller): remove unused deps ---------

  • refactor(pid_longitudinal_controller)!: prefix package and namespace with autoware (#7383)
    • add prefix
    • fix

    * fix trajectory follower node param ---------

  • Contributors: Esteve Fernandez, Kosuke Takeuchi, Satoshi OTA, Takayuki Murooka, Yuki TAKAGI, Yutaka Kondo, Zhe Shen, awf-autoware-bot[bot], mkquda, oguzkaganozt

0.26.0 (2024-04-03)

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged autoware_pid_longitudinal_controller at Robotics Stack Exchange

No version for distro noetic. Known supported distros are highlighted in the buttons above.
No version for distro ardent. Known supported distros are highlighted in the buttons above.
No version for distro bouncy. Known supported distros are highlighted in the buttons above.
No version for distro crystal. Known supported distros are highlighted in the buttons above.
No version for distro eloquent. Known supported distros are highlighted in the buttons above.
No version for distro dashing. Known supported distros are highlighted in the buttons above.
No version for distro galactic. Known supported distros are highlighted in the buttons above.
No version for distro foxy. Known supported distros are highlighted in the buttons above.
No version for distro iron. Known supported distros are highlighted in the buttons above.
No version for distro lunar. Known supported distros are highlighted in the buttons above.
No version for distro jade. Known supported distros are highlighted in the buttons above.
No version for distro indigo. Known supported distros are highlighted in the buttons above.
No version for distro hydro. Known supported distros are highlighted in the buttons above.
No version for distro kinetic. Known supported distros are highlighted in the buttons above.
No version for distro melodic. Known supported distros are highlighted in the buttons above.