INTRODUCTION
SPOT is a four-legged canine-inspired robot from Boston Dynamics that was unveiled in 2016, became commercially available in 2019, and was adopted by the Massachusetts State Police that same year.
The robot’s legs carry it up to 1.6 m/s [3.5 MPH] up and down slopes of 30° and steps as high as 30 cm [1 ft]. Onboard sensors include a 360° field of view from built-in monochrome stereo cameras with a 4m [13 ft] range. Spot can autonomously navigate around obstacles while running for 90 minutes on a swappable battery. It builds a map in real-time from the cameras. The SDK was made available in January of 2020.
Clearpath Robotics released a ROS driver for Spot in September of 2020. My work utilized that driver to develop a Gazebo SDF file for Spot based on the information in the driver, and a MATLAB-Simulink controller to allow Spot to stand and trot in place in Gazebo.
Spot URDF
The Spot URDF from Clearpath is made up of the base, front and rear rail links, and 3 links for each leg all connected with revolute joints.
The hip joint is constrained ±45° from the body around the x-axis.
The upper leg is constrained at the hip -51.5° to +131.5° around the y axis.
The knee joint constrains the upper leg and lower leg -160° to -14.6° around the y axis.
The figures below show a few visualizations of the URDF model in RVIZ using the joint state publisher to configure some poses. The visualization comes from roslaunch spot_rviz view_model.launch after cloning, building, and sourcing the driver in Melodic on Ubuntu 18.04.
Spot SDF
Gazebo can utilize URDF files directly, but with limitations. The preferred method to fully utilize the features of Gazebo is to create an SDF file for Spot, based on the information in the URDF and the meshes provided for the links.
The effort required slight modifications to the syntax between URDF and SDF, small changes to the pose values due to differences in how parent/child elements are referenced, and the addition of link mass and joint friction.
I attempted to obtain inertia values from each STL file with MeshLab but the solid collision files are missing too much detail to provide an adequate number. The simulation was unstable so I set all inertias to zero and based the mass of each link using the volume of each link and a uniform density. I created a custom grass ground plane to give the simulation more realism.
Both the Spot and Grass models should be placed somewhere that Gazebo can find them, such as /usr/share/gazebo-9/models on my Ubuntu VM. Then when you run Gazebo you can insert them into an empty world, resulting in the scene from the figure shown. My spotSim.world file, inside the spot_gazebo package, includes the grass model, a sun, Spot, and the GazeboPlugin required by MATLAB.
MATLAB-Gazebo Interface
The Gazebo plugin from Mathworks must be installed in Ubuntu to allow MATLAB-Simulink to communicate with Gazebo. The documentation says it requires Gazebo9, which I’m using, but I know from experience it also works with Gazebo11 if you update the CMakeLists.txt file.
Once installed the plugin must be referenced in the world file with the correct port number. I’m using port 11346. The filename field points to the compiled Gazebo plugin. The path was added to the Gazebo plugin search path by running the following where USR is the user directory name.
The Simulink Model spotController.slx shown in the next figure contains the Gazebo Sync Manager, the SPOT Gazebo Model interface, and the Simulink Leg Controller.
The Gazebo Sync Manager uses the Gazebo Pacer to setup the link to the running Gazebo simulation and pace the data transfer at the specified data rate.
The SPOT Gazebo Model includes both the feedback from the published nodes for the links and the individual joint torque commands.
The Simulink Leg Controller
Includes a Trot Controller to manage joint angle commands to get Spot to trot
Utilizes PID feedback controllers to command the torque required for each joint (hip x, hip y, and knee) to obtain the commanded angle
Standing
An angle of zero degrees corresponds to hips straight out, and both leg segments pointed straight down. This was the first pose attempted from rest. The joints had no friction or damping so the model was expected to be a unstable. The simulation always begins with the robot being dropped from a height of 4’ above the grass ground plane. The initial gains for the PD controllers were obtained from testing open loop torque commands. There was oscillation observed in the hip joint’s x axis which I first thought required improved tuning, but when I played with it a bit more I noticed that the left and right hips should have different signed commands (left positive and right negative). The figure below is a hip_x command from 0 degrees to splayed out to 18 degrees with Spot shown at t=10s, the final pose. The legs are being controlled straight.
Walking
Walking was the next goal for the SDF in Gazebo. To try and determine the proper CPG (central pattern generator) for the 12 joints to perform open loop walking, I reviewed a video of Spot walking. This was more valuable than studying canine walking since Spot doesn’t have the exact same dof as an actual dog. I imported the video into an editor and watched portions in slow motion. The initial trot into the camera frame is what I want to be able to emulate, though it was the transition from standing still to walking off that gave me the best clue: the legs start to trot in place before the robot starts to walk forward. I break down the trot-in-place pattern in the following table.
Starting with sinusoidal waveforms, the next table shows the derived joint positions for the front legs which were estimated and then simulated using trapezoidal waveforms. This is because the supporting legs don’t appear to straighten up while the other legs are moving down – they stay bent until the downward moving legs are all the way to the ground.
The assumption is that the hip_x angles remain constant at 0 degrees.
The upper leg is assumed to be the same length as the lower leg which is used to solve for the required knee angle for a corresponding hip_y angle.
The rear leg angles correspond to the opposite front angles.
Angles are in degrees to be more intuitive, and then converted to radians in the simulation.
Trapezoidal commands were generated using the 3rd, 5th, 7th, 9th, and 11th harmonics as shown in the following figures. I created a test bed called patternTestbed.slx to assist with generating the position commands.
Spot was able to perform this trot, but quickly became unstable and fell over sideways. There’s no control loop to ensure that Spot’s body stays level and balanced. I decided to try and use Spot’s hip_x joints to keep the body level, but instead of using a feedback control system I simply increased the friction in the joints. This allowed Spot to stay balanced while trotting in place. I also noticed that Spot was pitched up slightly when using 20 degrees for the offset in both the front and the back legs. I adjusted to 23 degrees for the front and 20 degrees for the back to get a level body.
The next step was to improve the controller performance from that shown in the following figure to follow the trapezoidal commands. An increase in the gain for the hip_y and knee joints allowed the joints to match the trapezoidal commands, even at higher frequencies, as seen in the lower half of the figure. I also added a slight integral gain. The Spot model can trot in place, and the next step is to investigate how Spot moves forward and back and rotates around. These are probably discoverable from the same video that I have used so far.