This assumes you are running from the Lab Speedgoat PC which already has the required dependencies installed
- Attach robot to the boom
- Connect power and 5 pin CAN to the robot
- Power on and index the boom
- Ensure the legs are free to move and that upper links are horizontal
- Turn on 48V supply to the ODrive and allow the legs to find their index points
- Add the
kinematics
folder to the Matlab path - Open and start
demo.slx
on the Speedgoat - The green controller button will start the robot hopping and holding the red button will stop
Discrete state controller based on the Raibert controller 1
stateDiagram-v2
direction LR
[*] --> Rest
Rest --> Thrust: Start
Compression --> Rest: Stop
Thrust --> Unloading: T1
Unloading --> Flight: T2
Flight --> Compression: T3
Compression --> Thrust: T4
The controller cycles through 5 discrete states defined in States.m
which sequences the control actions.
State | Control Action |
---|---|
Rest | Moderately stiff and damped leg to keep the body upright and standing |
Thrust | Small thrust force in the |
Unloading | Stop applying a thrust force and let the leg retract back to its neutral point |
Flight | Adjust |
Compression | Zero leg |
Transitions between controller states are triggered by changes in the robot state.
Transition | Trigger |
---|---|
Start | Green start button pressed on controller |
T1 | Leg has extended past its neutral length ( |
T2 | Foot has left the ground ( |
T3 | Leg is being compressed ( |
T4 | Leg is fully compressed and has begun extending ( |
Stop | Red stop button pressed on controller |
The leg is controlled in polar coordinates with a radial length
This ignores the mass and dynamics of the legs, but is still a reasonable approximation as the links are relatively light. A PD controller on each of the polar axes enables tracking of desired position and velocity setpoints
These PD controllers behave like a parallel spring and damper where
NB: If the
Hopping height is controlled by the radial thrust force. In an ideal world no thrust force should be required and the leg should be able to bounce up and down from an initial height on its perfectly springy leg indefinitely. Due to the motors not producing an ideal radial spring behaviour a small thrust force is required to maintain a desired hopping height. Higher thrust forces will produce greater hopping heights, but the downside to this (apart from the motors getting hotter) is that the radial leg force becomes less and less symmetric. For an ideal Raibert hopper the radial leg force is an even function of time. With a thrust force, the radial force for leg compression and extension is no longer the same producing net horizontal accelerations and impacting horizontal velocity control. For this reason the thrust force should be kept to a minimum and velocity control will most likely need to be adjusted if the thrust force is changed.
The neutral point is given by
with
Small changes in foot placement can produce large changes in body velocity. When tuning the gain
The encoders in the motors are mounted to the rotor. Because of the planetary reduction, one turn of the motor output results in six turns of the rotor. There are therefore six encoder index points for a full turn of the motor output/hip. It is therefore important that the hips start close (< 60°) to the correct one of these six index points. Powering on the ODrive with the upper links horizontal should accomplish this. When powered on, the ODrive will move the right motor CCW and the left motor CW until the index pulse is detected.
- Open the
kinematics
folder in matlab - Update
la.x
andla.y
incompute_kinematics.m
with the new foot dimensions - Run
compute_kinematics.m
to update function files
To configure the ODrive with correct motor and CAN parameters, and run motor calibration.
- Remove the legs
- Power ODrive with 48V
- Connect ODrive to PC
- Run
odrive-config.py
, this requires you to install odrivetool
Simulink will not show ODrive error messages. To get useful ODrive error messages follow these steps
- Keep simulink running - terminating will clear errors
- Start odrivetool and connect
- Run the
dump_errors(odrv0)
command and look here for the corresponding error
- Simulink
- Simulink Coder
- Simulink Real-Time
- Simulink Real-Time Target Support Package
- ARU Simulink Toolbox
- Speedgoat I/O Blockset
Footnotes
-
Raibert, M.H., 1986. Legged robots that balance. MIT press. ↩