Taking your Robot for a walk

Robots are great fun! But they're also expensive, which makes it a big investment to play around with them. But why not just simulate a robot? Well, that can also easily take several weeks of figuring out how to install which software.

At JuliaCon 2019 we had the pleasure to sit together and set up all the packages from Julia Robotics that are needed to make a robot walk. The software is mainly written by Twan Koolen and Robin. It's fairly trivial to set up if you know what's needed - and it offers competitive speed to established, complex, C++-based software.

We're visualizing the robot with Simon Danisch's plotting library, namely Makie.

The great news is that this notebook is fully reproducible! You can just press remix, run this notebook online, et voilà: you have your own robot that you can take for a walk.

For anyone without the patience to remix & run this article, here is a pre-rendered GIF showing the final result:

Let's cut the chit-chat and set up our robot. First, we'll import relevant packages, and include some more visualization and controller code.

robot_utils.jl
using RigidBodySim, MathOptInterface, MechanismGeometries, QPControl
using OSQP, QPWalkingControl, RigidBodyDynamics, AtlasRobot, LinearAlgebra
include(
robot_utils.jl
) JSServe.__init__(); # initialize the visualization library

We can now load our robot (an earlier version of the Boston Dynamics Atlas robot), represented as a kinematic tree, where the vertices represent links (rigid bodies) and the edges represent the joints that connect the links.

mechanism = AtlasRobot.mechanism(add_flat_ground = true)

We can load the associated visualization geometries:

vis_elements = visual_elements(
  mechanism,
  URDFVisuals(AtlasRobot.urdfpath(),
  package_path=[AtlasRobot.packagepath()])
);

and visualize Atlas in a nominal standing configuration:

nominal_state = MechanismState(mechanism)
AtlasRobot.setnominal!(nominal_state)
scene, meshes = set_up_scene(vis_elements);
display, three_js_display = create_display(scene)
set_state(three_js_display, meshes, vis_elements, nominal_state)
display

Next, we'll create the controller that will allow Atlas to walk around on flat ground. Explaining precisely what's going on is beyond the scope of this article, but if you're interested, see this paper for details.

The particular type of controller used for this demo consists of a low-level momentum-based motion controller and a high-level controller that implements the walking behavior on top of the low-level controller. The low-level controller sets up and solves a quadratic program (QP) at every control time step (here, at 500 Hz). We're using the Parametron.jl package to efficiently set up the QPs and hand them to a QP solver, in this case the osqp solver via its Julia wrapper package:

optimizer = OSQP.Optimizer(
  verbose=false, eps_abs=1e-5, eps_rel=1e-5, max_iter=5000
);

Wiping a lot of details under the rug, we can now create a walking controller based on this optimizer:

controller = atlas_controller(mechanism, nominal_state, optimizer);

Now we can start setting up the simulation. We're using RigidBodySim.jl, which uses DifferentialEquations.jl under the hood.

The controller will run at a simulated 500 Hz. To simulate this, we wrap our walking controller in a so-called PeriodicController and create a Dynamics object, which represents the dynamics of our robot with this controller in the loop:

pcontroller = PeriodicController(
  similar(velocity(nominal_state)),
  1 / 500,
  controller
)
dynamics = Dynamics(mechanism, pcontroller);

To visualize the robot during the simulation, we'll set up a callback that periodically updates the transforms of the mechanism's links to match the current state of the simulation:

scene, meshes = set_up_scene(vis_elements);
display, three_js_display = create_display(scene)
callback = VisUpdater(mechanism, three_js_display, meshes, vis_elements);
set_state(three_js_display, meshes, vis_elements, nominal_state)
display

Finally, we create and solve the ODEProblem representing a 15-second simulation:

sleep(4) # give server some time to finish showing the visualization
problem = ODEProblem(dynamics, nominal_state, (0.0, 15.0); callback=callback);
@time solve(problem, Tsit5(), abs_tol = 1e-8, dt = 1e-6);