tactics2d.controller
Controller module.
AccelerationController
Bases: ControllerBase
This class defines a controller that outputs acceleration command of the vehicle. The acceleration is calculated based on proportional control.
The controller supports two modes: - Cruise control: maintains a target speed using proportional gain. - Adaptive cruise control (ACC): adjusts speed based on leading vehicle state.
Attributes:
-
kp(float) –The proportional gain for speed error adjustment. The default value is 3.5. It can be adjusted by
update_driving_style. -
speed_factor(float) –The factor to adjust the target speed based on the driving style. The default value is 1.0. It can be adjusted by
update_driving_style. -
accel_change_rate(float) –The limitation to how quickly the acceleration can change over time to ensure smooth transitions. The unit is \(m^2\)/s. The default value is 3.0. It can be adjusted by
update_driving_style. -
max_accel(float) –The upper limit of the acceleration. The unit is \(m^2\)/s. The default value is 1.5. It can be adjusted by
update_driving_style. -
min_accel(float) –The lower limit of the acceleration. When negative, it describes the upper limit of the deceleration. The unit is \(m^2\)/s. The default value is -4.0. It can be adjusted by
update_driving_style. -
interval(float) –The time interval between the current command and the next. The unit is second. The default value is 2.0. It can be adjusted by
update_driving_style. -
delta_t(float) –The discrete time step for the simulation. The unit is millisecond. The default value is 0.05.
step(ego_state, **kwargs)
This method outputs the acceleration and steering command based on the current state of the ego vehicle.
Parameters:
-
ego_state(State) –The current state of the vehicle.
-
**kwargs–Additional inputs. May include: front_state (State): State of the leading vehicle for adaptive cruise control.
Returns:
-
steer(float) –The steering command for the ego vehicle. It is always zero for the acceleration controller.
-
accel(float) –The acceleration command for the ego vehicle.
update_driving_style(style_id)
This method allows to adopt the controller's behavior by adjusting the internal parameters.
Parameters:
-
style_id(float) –The driving style index, typically in range [-1.0, 1.0]. Values outside this range will be clamped via extrapolation.
ControllerBase
Bases: ABC
Abstract base class for all controllers in Tactics2D.
Controllers are responsible for converting high-level goals into low-level control commands (steering, acceleration). Each controller implements a specific control algorithm (e.g., PID, pure pursuit, IDM) and must define how to compute control outputs given the current state and optional additional inputs.
__repr__()
String representation of the controller.
configure(**kwargs)
Configure controller parameters.
Update controller parameters dynamically. Subclasses should override this to validate and apply parameter updates.
Parameters:
-
**kwargs–Parameter names and values to update.
create_style_interpolator(y_left, y_right, x_left=-1.0, x_right=1.0)
staticmethod
Create a linear interpolator for driving style adjustment.
Parameters:
-
y_left(float) –Parameter value at style_id = x_left (typically -1.0).
-
y_right(float) –Parameter value at style_id = x_right (typically 1.0).
-
x_left(float, default:-1.0) –Left bound of style_id range. Default -1.0.
-
x_right(float, default:1.0) –Right bound of style_id range. Default 1.0.
Returns:
-
interp1d–Linear interpolator with bounds_error=False and fill_value=(y_left, y_right).
reset()
Reset the controller's internal state.
This method should be called when the simulation resets or the controller is reused. Default implementation does nothing.
step(ego_state, **kwargs)
abstractmethod
Compute control commands for the ego vehicle.
This is the main interface for controllers. Subclasses must implement this method to compute steering and acceleration commands based on the current ego state and any additional required inputs.
Parameters:
-
ego_state(State) –Current state of the ego vehicle.
-
**kwargs–Additional inputs required by specific controllers (e.g., leading_state, waypoints, wheel_base).
Returns:
-
Tuple[float, float]–Tuple[float, float]: (steering, acceleration) commands. steering: Steering angle in radians. acceleration: Acceleration in m/s².
IDMController
Bases: ControllerBase
Intelligent Driver Model (IDM) controller for car-following behavior.
The IDM is a car-following model that computes acceleration based on: - Current speed and desired speed - Distance to leading vehicle (if present) - Relative speed to leading vehicle (if present)
Attributes:
-
desired_speed(float) –Desired speed in free traffic (m/s).
-
time_headway(float) –Desired time headway to leading vehicle (s).
-
min_spacing(float) –Minimum desired net distance to leading vehicle (m).
-
max_acceleration(float) –Maximum acceleration capability (m/s²).
-
comfortable_deceleration(float) –Comfortable deceleration (m/s²).
-
delta(float) –Acceleration exponent (usually 4.0).
__init__(desired_speed=10.0, time_headway=1.5, min_spacing=2.0, max_acceleration=1.0, comfortable_deceleration=3.0, delta=4.0)
Initialize IDM controller with parameters.
Parameters:
-
desired_speed(float, default:10.0) –Desired speed in free traffic (m/s). Default 10.0.
-
time_headway(float, default:1.5) –Desired time headway to leading vehicle (s). Default 1.5.
-
min_spacing(float, default:2.0) –Minimum desired net distance to leading vehicle (m). Default 2.0.
-
max_acceleration(float, default:1.0) –Maximum acceleration capability (m/s²). Default 1.0.
-
comfortable_deceleration(float, default:3.0) –Comfortable deceleration (m/s²). Default 3.0.
-
delta(float, default:4.0) –Acceleration exponent (usually 4.0). Default 4.0.
configure(**kwargs)
Configure IDM parameters.
Parameters:
-
**kwargs–Parameter names and values to update. Supported parameters: desired_speed, time_headway, min_spacing, max_acceleration, comfortable_deceleration, delta.
step(ego_state, leading_state=None, **kwargs)
Compute control commands using IDM.
Parameters:
-
ego_state(State) –Current state of the ego vehicle.
-
leading_state(State, default:None) –State of the leading vehicle (optional). If None, free-flow acceleration is used.
-
**kwargs–Additional arguments (ignored).
Returns:
-
Tuple[float, float]–Tuple[float, float]: (steering, acceleration) commands. steering is always 0.0 (pure longitudinal control). acceleration is computed by IDM (m/s²).
PIDController
Bases: ControllerBase
PID controller for combined lateral and longitudinal vehicle control.
This controller implements PID control for both steering (lateral) and acceleration (longitudinal) control. It supports driving style adjustment through linear interpolation of PID parameters.
The controller supports three control modes: - 'combined': Both lateral and longitudinal control (default) - 'lateral': Only steering control (acceleration = 0) - 'longitudinal': Only acceleration control (steering = 0)
Attributes:
-
dt(float) –Control time step in seconds.
-
control_mode(str) –Control mode - 'combined', 'lateral', or 'longitudinal'.
-
kp_lat(float) –Proportional gain for lateral control.
-
ki_lat(float) –Integral gain for lateral control.
-
kd_lat(float) –Derivative gain for lateral control.
-
max_steering(float) –Maximum steering angle in radians.
-
kp_lon(float) –Proportional gain for longitudinal control.
-
ki_lon(float) –Integral gain for longitudinal control.
-
kd_lon(float) –Derivative gain for longitudinal control.
-
max_accel(float) –Maximum acceleration in m/s².
-
min_accel(float) –Minimum acceleration (maximum deceleration) in m/s².
__init__(dt=0.05, control_mode='combined', kp_lat=1.5, ki_lat=0.2, kd_lat=0.5, max_steering=0.5, kp_lon=2.0, ki_lon=0.3, kd_lon=0.4, max_accel=3.0, min_accel=-5.0, derivative_filter_alpha=0.1)
Initialize PID controller with parameters.
Parameters:
-
dt(float, default:0.05) –Control time step in seconds. Default 0.05.
-
control_mode(str, default:'combined') –Control mode - 'combined', 'lateral', or 'longitudinal'. Default 'combined'.
-
kp_lat(float, default:1.5) –Proportional gain for lateral control. Default 1.5.
-
ki_lat(float, default:0.2) –Integral gain for lateral control. Default 0.2.
-
kd_lat(float, default:0.5) –Derivative gain for lateral control. Default 0.5.
-
max_steering(float, default:0.5) –Maximum steering angle in radians. Default 0.5 (~28.6°).
-
kp_lon(float, default:2.0) –Proportional gain for longitudinal control. Default 2.0.
-
ki_lon(float, default:0.3) –Integral gain for longitudinal control. Default 0.3.
-
kd_lon(float, default:0.4) –Derivative gain for longitudinal control. Default 0.4.
-
max_accel(float, default:3.0) –Maximum acceleration in m/s². Default 3.0.
-
min_accel(float, default:-5.0) –Minimum acceleration (maximum deceleration) in m/s². Default -5.0.
-
derivative_filter_alpha(float, default:0.1) –Low-pass filter coefficient for derivative term. Range (0, 1]. Smaller values = more filtering. Default 0.1.
Raises:
-
ValueError–If control_mode is invalid or parameters are out of valid ranges.
configure(**kwargs)
Configure controller parameters.
Parameters:
-
**kwargs–Parameter names and values to update. Supported parameters: dt, control_mode, kp_lat, ki_lat, kd_lat, max_steering, kp_lon, ki_lon, kd_lon, max_accel, min_accel, derivative_filter_alpha.
Raises:
-
AttributeError–If parameter name is not recognized.
-
ValueError–If parameter value is invalid.
reset()
Reset the controller's internal state.
Clears integral accumulators and previous error values.
step(ego_state, **kwargs)
Compute PID control commands for combined lateral and longitudinal control.
Parameters:
-
ego_state(State) –Current state of the ego vehicle.
-
**kwargs–Additional inputs required for control: For lateral control: 'target_heading' (float) or 'cross_track_error' (float) For longitudinal control: 'target_speed' (float) Optional: 'wheel_base' (float) for lateral control calculations (used to convert cross-track error to steering angle if needed).
Returns:
-
Tuple[float, float]–Tuple[float, float]: (steering_angle, acceleration) commands. steering_angle: Steering angle in radians. acceleration: Acceleration in m/s².
Raises:
-
ValueError–If required inputs are missing or invalid.
-
TypeError–If input types are incorrect.
update_driving_style(style_id)
Update controller parameters based on driving style.
Parameters:
-
style_id(float) –Driving style index in range [-1.0, 1.0]. -1.0: Conservative driving style (smooth, cautious) 0.0: Normal driving style (default parameters) 1.0: Aggressive driving style (responsive, aggressive) Values outside range are extrapolated linearly.
Raises:
-
TypeError–If style_id is not int or float.
PurePursuitController
Bases: ControllerBase
This class implements a pure pursuit controller to output steering and acceleration commands of the vehicle.
The controller combines lateral control (pure pursuit algorithm) with longitudinal control (via an AccelerationController). It tracks a path defined by waypoints and computes steering angle to follow a look-ahead point.
Attributes:
-
interval(float) –The time interval between the current command and the next. The unit is second. The default value is 1.0. It can be adjusted by
update_driving_style.
step(ego_state, waypoints, wheel_base=2.637, **kwargs)
This method outputs the acceleration and steering command based on the current state of the ego vehicle.
Parameters:
-
ego_state(State) –Current state of the ego vehicle.
-
waypoints(LineString) –Path to follow as a Shapely LineString.
-
wheel_base(float, default:2.637) –The wheelbase of the ego vehicle in meters. Defaults to 2.637 (medium car).
-
**kwargs–Additional inputs passed to the longitudinal controller. May include front_state (State) for adaptive cruise control.
Returns:
-
steering(float) –The steering command for the ego vehicle in radians.
-
accel(float) –The acceleration command for the ego vehicle in m/s².
update_driving_style(style_id)
This method allows to adopt the controller's behavior by adjusting the internal parameters.
Parameters:
-
style_id(float) –The driving style index, typically in range [-1.0, 1.0]. Values outside this range will be clamped via extrapolation.