Control¶
The ControlledVehicle
class implements a low-level controller on top of a Vehicle
, allowing to track a given target speed and follow a target lane.
The controls are computed when calling the act()
method.
Longitudinal controller¶
The longitudinal controller is a simple proportional controller:
where
\(a\) is the vehicle acceleration (throttle);
\(v\) is the vehicle velocity;
\(v_r\) is the reference velocity;
\(K_p\) is the controller proportional gain, implemented as
KP_A
.
It is implemented in the speed_control()
method.
Lateral controller¶
The lateral controller is a simple proportional-derivative controller, combined with some non-linearities that invert those of the kinematics model.
Position control¶
Heading control¶
where
\(\Delta_{\text{lat}}\) is the lateral position of the vehicle with respect to the lane center-line;
\(v_{\text{lat},r}\) is the lateral velocity command;
\(\Delta \psi_{r}\) is a heading variation to apply the lateral velocity command;
\(\psi_L\) is the lane heading (at some lookahead position to anticipate turns);
\(\psi_r\) is the target heading to follow the lane heading and position;
\(\dot{\psi}_r\) is the yaw rate command;
\(\delta\) is the front wheels angle control;
\(K_{p,\text{lat}}\) and \(K_{p,\psi}\) are the position and heading control gains.
It is implemented in the steering_control()
method.
API¶
-
class
highway_env.vehicle.controller.
ControlledVehicle
(road: highway_env.road.road.Road, position: Union[numpy.ndarray, Sequence[float]], heading: float = 0, speed: float = 0, target_lane_index: Tuple[str, str, int] = None, target_speed: float = None, route: List[Tuple[str, str, int]] = None)[source]¶ A vehicle piloted by two low-level controller, allowing high-level actions such as cruise control and lane changes.
The longitudinal controller is a speed controller;
The lateral controller is a heading controller cascaded with a lateral position controller.
-
TAU_A
= 0.6¶
-
TAU_DS
= 0.2¶
-
PURSUIT_TAU
= 0.30000000000000004¶
-
KP_A
= 1.6666666666666667¶
-
KP_HEADING
= 5.0¶
-
KP_LATERAL
= 1.6666666666666665¶
-
MAX_STEERING_ANGLE
= 1.0471975511965976¶
-
DELTA_SPEED
= 5¶
-
__init__
(road: highway_env.road.road.Road, position: Union[numpy.ndarray, Sequence[float]], heading: float = 0, speed: float = 0, target_lane_index: Tuple[str, str, int] = None, target_speed: float = None, route: List[Tuple[str, str, int]] = None)[source]¶ Initialize self. See help(type(self)) for accurate signature.
-
target_speed
: float = None¶ Desired velocity.
-
classmethod
create_from
(vehicle: highway_env.vehicle.controller.ControlledVehicle) → highway_env.vehicle.controller.ControlledVehicle[source]¶ Create a new vehicle from an existing one.
The vehicle dynamics and target dynamics are copied, other properties are default.
- Parameters
vehicle – a vehicle
- Returns
a new vehicle at the same dynamical state
-
plan_route_to
(destination: str) → highway_env.vehicle.controller.ControlledVehicle[source]¶ Plan a route to a destination in the road network
- Parameters
destination – a node in the road network
-
act
(action: Union[dict, str] = None) → None[source]¶ Perform a high-level action to change the desired lane or speed.
If a high-level action is provided, update the target speed and lane;
then, perform longitudinal and lateral control.
- Parameters
action – a high-level action
-
steering_control
(target_lane_index: Tuple[str, str, int]) → float[source]¶ Steer the vehicle to follow the center of an given lane.
Lateral position is controlled by a proportional controller yielding a lateral speed command
Lateral speed command is converted to a heading reference
Heading is controlled by a proportional controller yielding a heading rate command
Heading rate command is converted to a steering angle
- Parameters
target_lane_index – index of the lane to follow
- Returns
a steering wheel angle command [rad]
-
speed_control
(target_speed: float) → float[source]¶ Control the speed of the vehicle.
Using a simple proportional controller.
- Parameters
target_speed – the desired speed
- Returns
an acceleration command [m/s2]
-
get_routes_at_intersection
() → List[List[Tuple[str, str, int]]][source]¶ Get the list of routes that can be followed at the next intersection.
-
set_route_at_intersection
(_to: int) → None[source]¶ Set the road to be followed at the next intersection.
Erase current planned route.
- Parameters
_to – index of the road to follow at next intersection, in the road network
-
predict_trajectory_constant_speed
(times: numpy.ndarray) → Tuple[List[numpy.ndarray], List[float]][source]¶ Predict the future positions of the vehicle along its planned route, under constant speed
- Parameters
times – timesteps of prediction
- Returns
positions, headings
-
__annotations__
= {'target_speed': <class 'float'>}¶
-
__module__
= 'highway_env.vehicle.controller'¶
-
class
highway_env.vehicle.controller.
MDPVehicle
(road: highway_env.road.road.Road, position: List[float], heading: float = 0, speed: float = 0, target_lane_index: Tuple[str, str, int] = None, target_speed: float = None, route: List[Tuple[str, str, int]] = None)[source]¶ A controlled vehicle with a specified discrete range of allowed target speeds.
-
SPEED_COUNT
: int = 3¶
-
SPEED_MIN
: float = 20¶
-
SPEED_MAX
: float = 30¶
-
__init__
(road: highway_env.road.road.Road, position: List[float], heading: float = 0, speed: float = 0, target_lane_index: Tuple[str, str, int] = None, target_speed: float = None, route: List[Tuple[str, str, int]] = None) → None[source]¶ Initialize self. See help(type(self)) for accurate signature.
-
act
(action: Union[dict, str] = None) → None[source]¶ Perform a high-level action.
If the action is a speed change, choose speed from the allowed discrete range.
Else, forward action to the ControlledVehicle handler.
- Parameters
action – a high-level action
-
classmethod
index_to_speed
(index: int) → float[source]¶ Convert an index among allowed speeds to its corresponding speed
- Parameters
index – the speed index []
- Returns
the corresponding speed [m/s]
-
__annotations__
= {'SPEED_COUNT': <class 'int'>, 'SPEED_MAX': <class 'float'>, 'SPEED_MIN': <class 'float'>}¶
-
__module__
= 'highway_env.vehicle.controller'¶
-
classmethod
speed_to_index
(speed: float) → int[source]¶ Find the index of the closest speed allowed to a given speed.
- Parameters
speed – an input speed [m/s]
- Returns
the index of the closest speed allowed []
-
predict_trajectory
(actions: List, action_duration: float, trajectory_timestep: float, dt: float) → List[highway_env.vehicle.controller.ControlledVehicle][source]¶ Predict the future trajectory of the vehicle given a sequence of actions.
- Parameters
actions – a sequence of future actions.
action_duration – the duration of each action.
trajectory_timestep – the duration between each save of the vehicle state.
dt – the timestep of the simulation
- Returns
the sequence of future states
-