Vehicle abstract baseclass
- class roboticstoolbox.mobile.VehicleBase(covar=None, speed_max=inf, accel_max=inf, x0=[0, 0, 0], dt=0.1, control=None, seed=0, animation=None, verbose=False, plot=False, workspace=None, polygon=None)[source]
- __init__(covar=None, speed_max=inf, accel_max=inf, x0=[0, 0, 0], dt=0.1, control=None, seed=0, animation=None, verbose=False, plot=False, workspace=None, polygon=None)[source]
Superclass for vehicle kinematic models
- Parameters:
covar (ndarray(2,2), optional) – odometry covariance, defaults to zero
speed_max (float, optional) – maximum speed, defaults to \(\infty\)
accel_max (float, optional) – maximum acceleration, defaults to \(\infty\)
x0 (array_like(3), optional) – Initial state, defaults to (0,0,0)
dt (float, optional) – sample update interval, defaults to 0.1
control (array_like(2), interp1d, VehicleDriverBase) – vehicle control inputs, defaults to None
animation (
VehicleAnimationBase
subclass, optional) – Graphical animation of vehicle, defaults to Noneverbose (bool, optional) – print lots of info, defaults to False
workspace (float, array_like(2), array_like(4)) – dimensions of 2D plot area, defaults to (-10:10) x (-10:10), see
plotvol2()
polygon (
Polygon2
) – bounding polygon of vehicle
This is an abstract superclass that simulates the motion of a mobile robot under the action of a controller. The controller provides control inputs to the vehicle, and the output odometry is returned. The true state, effectively unknowable in practice, is computed and accessible.
The workspace can be specified in several ways:
workspace
x-range
y-range
A (scalar)
-A:A
-A:A
[A, B]
A:B
A:B
[A, B, C, D]
A:B
C:D
- Note:
Set
seed=None
to have it randomly initialized from the operating system.- Seealso:
- __str__()[source]
String representation of vehicle (superclass)
- Returns:
String representation of vehicle object
- Return type:
- f(x, odo, v=None)[source]
State transition function
- Parameters:
x (array_like(3), ndarray(n,3)) – vehicle state \((x, y, \theta)\)
odo (array_like(2)) – vehicle odometry \((\delta_d, \delta_\theta)\)
v (array_like(2), optional) – additive odometry noise, defaults to (0,0)
- Returns:
predicted vehicle state
- Return type:
ndarray(3)
Predict the next state based on current state and odometry value.
v
is a random variable that represents additive odometry noise for simulation purposes.\[f: \vec{x}_k, \delta_d, \delta_\theta \mapsto \vec{x}_{k+1}\]For particle filters it is useful to apply the odometry to the states of all particles and this can be achieved if
x
is a 2D array with one state per row.v
is ignored in this case.Note
This is the state update equation used for EKF localization.
- Fx(x, odo)[source]
Jacobian of state transition function df/dx
- Parameters:
x (array_like(3)) – vehicle state \((x, y, \theta)\)
odo (array_like(2)) – vehicle odometry \((\delta_d, \delta_\theta)\)
- Returns:
Jacobian matrix
- Return type:
ndarray(3,3)
Returns the Jacobian matrix \(\frac{\partial \vec{f}}{\partial \vec{x}}\) for the given state and odometry.
- Fv(x, odo)[source]
Jacobian of state transition function df/dv
- Parameters:
x (array_like(3)) – vehicle state \((x, y, \theta)\)
odo (array_like(2)) – vehicle odometry \((\delta_d, \delta_\theta)\)
- Returns:
Jacobian matrix
- Return type:
ndarray(3,2)
Returns the Jacobian matrix \(\frac{\partial \vec{f}}{\partial \vec{v}}\) for the given state and odometry.
- property control
Get/set vehicle control (superclass)
- Getter:
Returns vehicle’s control
- Setter:
Sets the vehicle’s control
- Type:
2-tuple, callable, interp1d or VehicleDriver
This is the input to the vehicle during a simulation performed by
run()
. The control input can be:a constant tuple as the control inputs to the vehicle
a function called as
f(vehicle, t, x)
that returns a tuplean interpolator called as
f(t)
that returns a tuplea driver agent, subclass of
driversVehicleDriverBase
Example:
>>> from roboticstoolbox import Bicycle, RandomPath >>> bike = Bicycle() >>> bike.control = RandomPath(10) >>> print(bike) Bicycle: x = [ 0, 0, 0 ] L=1, steer_max=1.41372, speed_max=inf, accel_max=inf
- eval_control(control, x)[source]
Evaluate vehicle control input (superclass method)
- Parameters:
control ([type]) – vehicle control
x (array_like(3)) – vehicle state \((x, y, heta)\)
- Raises:
ValueError – bad control
- Returns:
vehicle control inputs
- Return type:
ndarray(2)
Evaluates the control for this time step and state. Control is set by the
control()
property to:a constant tuple as the control inputs to the vehicle
a function called as
f(vehicle, t, x)
that returns a tuplean interpolator called as f(t) that returns a tuple
a driver agent, subclass of
VehicleDriverBase
Vehicle steering, speed and acceleration limits are applied to the result before being input to the vehicle model.
- limits_va(v, v_prev)[source]
Apply velocity and acceleration limits (superclass)
- Parameters:
v (float) – desired velocity
v_prev (list with single element) – previous velocity, reference to list
- Returns:
allowed velocity
- Return type:
Determine allowable velocity given desired velocity, speed and acceleration limits.
Note
This function requires previous velocity,
v_prev
to enable acceleration limiting. This is passed as a reference to a mutable value, a single-element list. This is reset to zero at the start of each simulation.
- polygon(q)[source]
Bounding polygon at vehicle configuration
- Parameters:
q (array_like(3)) – vehicle configuration \((x, y, heta)\)
- Returns:
bounding polygon of vehicle at configuration
q
- Return type:
Polygon2
The bounding polygon of the vehicle is returned for the configuration
q
. Can be used for collision checking using theintersects()
method.- Seealso:
Polygon2
- add_driver(driver)[source]
Add a driver agent (superclass)
- Parameters:
driver (VehicleDriverBase subclass) – a driver agent object
Warning
Deprecated. Use
vehicle.control = driver
instead.- Seealso:
VehicleDriverBase
control()
- run(T=10, x0=None, control=None, animate=True)[source]
Simulate motion of vehicle (superclass)
- Parameters:
T (float, optional) – Simulation time in seconds, defaults to 10
x0 (array_like(3) or array_like(2)) – Initial state, defaults to value given to Vehicle constructor
control (array_like(2), callable, driving agent) – vehicle control inputs, defaults to None
animate (bool, optional) – Enable graphical animation of vehicle, defaults to False
- Returns:
State trajectory, each row is \((x,y,\theta)\).
- Return type:
ndarray(n,3)
Runs the vehicle simulation for
T
seconds and optionally plots an animation. The methodstep()
performs each time step.The control inputs are provided by
control
which can be:a constant tuple as the control inputs to the vehicle
a function called as
f(vehicle, t, x)
that returns a tuplean interpolator called as
f(t)
that returns a tuple, see SciPy interp1da driver agent, subclass of
VehicleDriverBase
This is evaluated by
eval_control()
which applies velocity, acceleration and steering limits.The simulation can be stopped prematurely by the control function calling
stopsim()
.Note
the simulation is fixed-time step with the step given by the
dt
attribute set by the constructor.integration uses rectangular integration.
- Seealso:
- run_animation(T=10, x0=None, control=None, format=None, file=None)[source]
Simulate motion of vehicle (superclass)
- Parameters:
T (float, optional) – Simulation time in seconds, defaults to 10
x0 (array_like(3) or array_like(2)) – Initial state, defaults to value given to Vehicle constructor
control (array_like(2), callable, driving agent) – vehicle control inputs, defaults to None
format (str, optional) – Output format
file (str, optional) – File name
- Returns:
Matplotlib animation object
- Return type:
matplotlib.animation.FuncAnimation()
Runs the vehicle simulation for
T
seconds and returns an animation in various formats:``format`` ``file`` description ============ ========= ============================ ``"html"`` str, None return HTML5 video ``"jshtml"`` str, None return JS+HTML video ``"gif"`` str return animated GIF ``"mp4"`` str return MP4/H264 video ``None`` return a ``FuncAnimation`` object
The allowables types for
file
are given in the second column. A str value is the file name. IfNone
is an option then return the video as a string.For the last case, a reference to the animation object must be held if used for animation in a Jupyter cell:
anim = robot.run_animation(T=20)
The control inputs are provided by
control
which can be:a constant tuple as the control inputs to the vehicle
a function called as
f(vehicle, t, x)
that returns a tuplean interpolator called as
f(t)
that returns a tuple, see SciPy interp1da driver agent, subclass of
VehicleDriverBase
This is evaluated by
eval_control()
which applies velocity, acceleration and steering limits.The simulation can be stopped prematurely by the control function calling
stopsim()
.Note
the simulation is fixed-time step with the step given by the
dt
attribute set by the constructor.integration uses rectangular integration.
- Seealso:
- init(x0=None, control=None, animate=True)[source]
Initialize for simulation (superclass)
- Parameters:
x0 (array_like(3) or array_like(2)) – Initial state, defaults to value given to Vehicle constructor
Performs the following initializations:
Clears the state history
Set the private random number generator to initial value
Sets state \(x = x_0\)
Sets previous velocity to zero
If a driver is attached, initialize it
If animation is enabled, initialize that
If animation is enabled by constructor and no animation object is given, use a default
VehiclePolygon("car")
- Seealso:
- step(u=None, animate=True, pause=True)[source]
Step simulator by one time step (superclass)
- Returns:
odometry \((\delta_d, \delta_\theta)\)
- Return type:
ndarray(2)
Obtain the vehicle control inputs
Integrate the vehicle state forward one timestep
Updates the stored state and state history
Update animation if enabled.
Returns the odometry
veh.step((vel, steer))
for a Bicycle vehicle modelveh.step((vel, vel_diff))
for a Unicycle vehicle modelveh.step()
as above but control is taken from thecontrol
attribute which might be a function or driver agent.
Example:
>>> from roboticstoolbox import Bicycle >>> bike = Bicycle() # default bicycle model >>> bike.step((1, 0.2)) # one step: v=1, γ=0.2 array([0.1 , 0.0203]) >>> bike.x array([0.1 , 0. , 0.0203]) >>> bike.step((1, 0.2)) # another step: v=1, γ=0.2 array([0.1 , 0.0203]) >>> bike.x array([0.2 , 0.002 , 0.0405])
Note
Vehicle control input limits are applied.
- property workspace
Size of robot workspace (superclass)
- Returns:
workspace bounds [xmin, xmax, ymin, ymax]
- Return type:
ndarray(4)
Returns the bounds of the workspace as specified by constructor option
workspace
- property x
Get vehicle state/configuration (superclass)
- Returns:
Vehicle state \((x, y, \theta)\)
- Return type:
ndarray(3)
- Seealso:
- property q
Get vehicle state/configuration (superclass)
- Returns:
Vehicle state \((x, y, \theta)\)
- Return type:
ndarray(3)
- Seealso:
- property x0
Get vehicle initial state/configuration (superclass)
- Returns:
Vehicle state \((x, y, \theta)\)
- Return type:
ndarray(3)
Set by
VehicleBase
subclass constructor. The state is set to this value at the beginning of each simulation run.- Seealso:
- property random
Get private random number generator
- Returns:
NumPy random number generator
- Return type:
Has methods including:
The generator is initialized with the seed provided at constructor time every time
init()
is called.- Seealso:
- property x_hist
Get vehicle state/configuration history (superclass)
- Returns:
Vehicle state history
- Return type:
ndarray(n,3)
The state \((x, y, heta)\) at each time step resulting from a simulation run, one row per timestep.
- Seealso:
- property speed_max
Get maximum speed of vehicle (superclass)
- Returns:
maximum speed
- Return type:
Set by
VehicleBase()
subclass constructor.- Seealso:
accel_max()
steer_max()
u_limited()
- property accel_max
Get maximum acceleration of vehicle (superclass)
- Returns:
maximum acceleration
- Return type:
Set by
VehicleBase()
subclass constructor.- Seealso:
speed_max()
steer_max()
u_limited()
- property dt
Get sample time (superclass)
- Returns:
discrete time step for simulation
- Return type:
Set by
VehicleBase()
subclass constructor. Used bystep()
to update state.- Seealso:
- property verbose
Get verbosity (superclass)
- Returns:
verbosity level
- Return type:
Set by
VehicleBase
subclass constructor.
- stopsim()[source]
Stop the simulation (superclass)
A control function can stop the simulation initated by the
run
method.- Seealso:
- plot_xy(*args, block=None, **kwargs)[source]
Plot xy-path from history
- Parameters:
The \((x,y)\) trajectory from the simulation history is plotted as \(x\) vs :math:`y.
- Seealso: