Details
Index
DiffEqBase.CallbackSet
DiffEqBase.ODEProblem
RigidBodySim.PeriodicController
RigidBodySim.any_open_visualizer_windows
RigidBodySim.configuration_renormalizer
RigidBodySim.new_visualizer_window
RigidBodySim.zero_control!
RigidBodyTreeInspector.animate
ODE problem creation
DiffEqBase.ODEProblem
— Type.ODEProblem(state, tspan)
ODEProblem(state, tspan, control!; callback)
Create a DiffEqBase.ODEProblem
representing the closed-loop dynamics of a RigidBodyDynamics.Mechanism
.
The initial state is given by the state
argument (a RigidBodyDynamics.MechanismState
). The state
argument will be modified during the simulation, as it is used to evaluate the dynamics.
The control!
argument is a callable with the signature control!(τ, t, state)
, where τ
is the torque vector to be set in the body of control!
, t
is the current time, and state
is a MechanismState
object. By default, control!
is zero_control!
.
The callback
keyword argument can be used to pass in additional DifferentialEquations.jl callbacks.
Examples
The following is a ten second simulation of the passive dynamics of an Acrobot (double pendulum) with a Vern7
integrator (see DifferentialEquations.jl documentation).
julia> using RigidBodySim, RigidBodyDynamics, OrdinaryDiffEq
julia> mechanism = parse_urdf(Float64, Pkg.dir("RigidBodySim", "test", "urdf", "Acrobot.urdf"))
Spanning tree:
Vertex: world (root)
Vertex: base_link, Edge: base_link_to_world
Vertex: upper_link, Edge: shoulder
Vertex: lower_link, Edge: elbow
No non-tree joints.
julia> state = MechanismState(mechanism);
julia> set_configuration!(state, [0.1; 0.2]);
julia> problem = ODEProblem(state, (0., 10.))
DiffEqBase.ODEProblem with uType Array{Float64,1} and tType Float64. In-place: true
timespan: (0.0, 10.0)
u0: [0.1, 0.2, 0.0, 0.0]
julia> solution = solve(problem, Vern7());
Control
RigidBodySim.zero_control!
— Function.zero_control!(τ, t, state)
A 'zero' controller, i.e. one that sets all control torques to zero at all times.
RigidBodySim.PeriodicController
— Type.struct PeriodicController{Tau, T<:Number, C, I}
A PeriodicController
can be used to simulate a digital controller that runs at a fixed rate (in terms of simulation time). It does so by performing a zero-order hold on a provided control function.
PeriodicController
s can be constructed using
PeriodicController(τ, Δt, control; initialize = DiffEqBase.INITIALIZE_DEFAULT, save_positions = (false, false))
where control
is a controller satisfying the standard RigidBodySim controller signature (control(τ, Δt, state)
), Δt
is the simulation time interval between calls to the control
function, and τ
is used to call control
. The initialize
and save_positions
keyword arguments are documented in the DiscreteCallback
section of the DifferentialEquations documentation.
PeriodicController
s are callable objects, and themselves fit the standard RigidBodySim controller signature.
A DiffEqCallbacks.PeriodicCallback
can be created from a PeriodicController
, and is used to stop ODE integration exactly every Δt
seconds, so that the controller can be called. Typically, users will not have to explicitly create this PeriodicCallback
, as it is automatically created and added to the ODEProblem
when the PeriodicController
is passed into the following DiffEqBase.ODEProblem
constructor overload:
ODEProblem(state, tspan, controller::PeriodicController; callback)
Examples
In the following example, a PeriodicController
is used to simulate a digital PD controller running at a fixed rate of 200 Hz.
julia> using RigidBodySim, RigidBodyDynamics, OrdinaryDiffEq
julia> mechanism = parse_urdf(Float64, Pkg.dir("RigidBodySim", "test", "urdf", "Acrobot.urdf"));
julia> state = MechanismState(mechanism);
julia> set_configuration!(state, [0.1; 0.2]);
julia> controlcalls = Ref(0);
julia> pdcontrol!(τ, t, state) = (controlcalls[] += 1; τ .= -20 .* velocity(state) .- 100 .* configuration(state));
julia> τ = zeros(velocity(state)); Δt = 1 / 200
0.005
julia> problem = ODEProblem(state, (0., 5.), PeriodicController(τ, Δt, pdcontrol!));
julia> sol = solve(problem, Tsit5());
julia> sol.u[end]
4-element Array{Float64,1}:
-3.25923e-5
-1.67942e-5
8.16715e-7
1.55292e-8
julia> @assert all(x -> isapprox(x, 0, atol = 1e-4), sol.u[end]) # ensure state converges to zero
julia> controlcalls[]
1001
Visualization
DiffEqBase.CallbackSet
— Method.CallbackSet(vis, state; max_fps)
Create the DifferentialEquations.jl callbacks needed for publishing to and receiving commands from a director visualizer instance during simulation.
max_fps
is the maximum number of frames per second (in terms of wall time) to draw. Default: 60.0
.
RigidBodySim.any_open_visualizer_windows
— Function.any_open_visualizer_windows()
Return whether any director visualizer windows are open.
RigidBodySim.new_visualizer_window
— Function.new_visualizer_window()
Open a new director visualizer window.
The director instance will be started with a script that handles communication between RigidBodySim.jl and the director instance.
RigidBodyTreeInspector.animate
— Method.animate(vis, state, sol; max_fps, realtime_rate, pause_pollint)
Play back a visualization of a DiffEqBase.ODESolution
obtained from a RigidBodySim.jl simulation.
vis
is a DrakeVisualizer.Visualizer
. The easiest way to create a Visualizer
for a robot is from a URDF, which can be parsed by RigidBodyTreeInspector.jl's parse_urdf
function.
state
is a RigidBodyDynamics.MechanismState
, representing the state of the mechanism that was simulated, and will be modified during the visualization.
animate
accepts the following keyword arguments:
max_fps
: the maximum number of frames per second to draw. Default:60.0
.realtime_rate
: can be used to slow down or speed up playback compared to wall time. Arealtime_rate
of2
will result in playback that is sped up 2x. Default:1.0
.pause_pollint
: how often to poll for commands coming from the director window when playback is paused. Default: 0.05.
Examples
Visualizing the result of a simulation of the passive dynamics of an Acrobot (double pendulum) at half speed:
julia> using RigidBodySim, RigidBodyDynamics, OrdinaryDiffEq, RigidBodyTreeInspector
julia> urdf = Pkg.dir("RigidBodySim", "test", "urdf", "Acrobot.urdf");
julia> mechanism = parse_urdf(Float64, urdf);
julia> state = MechanismState(mechanism);
julia> set_configuration!(state, [0.1; 0.2]);
julia> problem = ODEProblem(state, (0., 2.));
julia> sol = solve(problem, Vern7());
julia> any_open_visualizer_windows() || (new_visualizer_window(); sleep(1));
julia> vis = Visualizer(mechanism, parse_urdf(urdf, mechanism));
julia> animate(vis, state, sol; realtime_rate = 0.5);
Utilities
RigidBodySim.configuration_renormalizer
— Function.configuration_renormalizer(state)
configuration_renormalizer(state, condition)
configuration_renormalizer
can be used to create a callback that projects the configuration of a mechanism's state onto the configuration manifold. This may be necessary for mechanism's with e.g. quaternion-parameterized orientations as part of their joint configuration vectors, as numerical integration can cause the configuration to drift away from the unit norm constraints.
The callback is implemented as a DiffEqCallbacks.DiscreteCallback
By default, it is called at every integrator time step.