ArbotiX RoboController

The ArbotiX robocontroller is an Arduino compatible microcontroller board, designed to control small-to-medium sized robots, especially walkers that use Dynamixel AX or MX-series servos.

Support is typically handled through the very active user community found in the Trossen Robotics Community Forums. You can purchase an ArbotiX from Trossen Robotics. Please file tickets on GitHub.

PyPose is a related project for an open-source pose capture program. NUKE is a Nearly Universal Kinematics Engine included within PyPose.

NUKE Tuning

Overview of the IK Solution and Gait Engine

NUKE generates a full inverse kinematics solution and a gait engine for your robot. However, you may want to tune it by hand. Before you can tune a system though, you will need to know how it works.

NUKE exports 4 files:

The main loop of your program, in something.pde will look like this

void loop(){
// put your task code here
// make sure it doesn't take too long to execute each cycle

if(bioloid.interpolating == 0){
  // last step is done, do the next
  doIK();
  bioloid.interpolateSetup(tranTime);
}
bioloid.interpolateStep();
        

Your code will interact with the gait engine using several global variables, which can be set at any time, from anywhere in your code:

The body IK engine also relies on several other variables:

The most important function is clearly doIK() which ties everything from NUKE together. doIK() generates the IK solution for each leg's servos, taking into account the default positions (created in setupIK()), gait requests, and the bodyIK parameters such as body yaw or pitch. You should not need to alter the doIK(), bodyIK() or legIK(). Most of the optimization that end users can do is in setupIK() and the gait generators.

Basic Gaits

Basic gaits are cyclic. We can see that as a robot moves forward, it moves it's legs in some cyclic order. NUKE uses a gait generator function to create these movements. By passing in the leg ID and the step variable, the gait generator creates a set of offsets (X,Y,Z,rotation about Z) for the given leg at that step. The step variable counts from 0 to the number of steps in the currently selected gait -- this number is known as the stepsInCycle. For each cycle, every leg will move the desired distance (which is controlled by the speed variables).

A basic gait generator looks like this:

ik_req_t DefaultGaitGen(int leg){
 // TODO: add code here!!!!
}
        

By default, NUKE generates continuous gaits. Continuous gaits are such that the body moves in the desired direction at a continuous rate. A discontinuous gait is one that moves the body only when all feet are on the ground. When a gait is not stable enough, especially over terrain, creating a discontinuous gait may be of help.

Included Gaits

A number of gaits are included, which can be selected using the SelectGait() function: (NOTE: SOME GAITS NOT YET IN BETA)

Default Stance, Length of Stride as an Optimization Factor

NUKE computes the Configuration Space of your robot's legs. The configuration space is the region of space where the legs can actually touch without any servo going out of range. From this, it can find what the default stance should be in order to maximize stride.

For most quadrupeds and hexapods, this is a good starting place. However, you may find yourself wanting to tune the default stance. This can be done by editing the setupIK() function. setupIK sets the position of the servos when the robot first starts up, and this position is what we add gait requests and body rotation requests to when we compute the final leg positions at each step in our cycle.

Future versions of NUKE may also allow optimizations for maximal stability rather than stride length, however, at this point you would have to hand optimize for this, a first step would be the use of a Geometrically Stable gait.

Geometric Stability

This section describes a feature available only in NUKE V1.2 and above.

NUKE can generate a geometrically stable gait, that is, the Center-of-Gravity of the robot is always within the Support Polygon created by the feet that remain on the ground.

The Stability Margin is the shortest length from the COG to the support polygon as projected along the direction of gravity. What the heck does that mean? On an incline, your stability margin is less than on flat ground. Frequently, the stability margin may be difficult or impossible to determine, and so approximations are often used.

TODO: add images of stability margin/etc

Creating New Gait Generators

There are two steps to creating a new gait. First, you must create a new gait generator and possibly a new gait setup, and then add the gait to the SelectGait function.

TODO: add discussion of creating Gait Generators and Setup functions, the use of tranTime, etc

After creating your new gait, you need to add the ability to select the gait. To add a new gait to your SelectGait function, you will typically add to the end of the long set of if/else statements:

...
}else if(GaitType == MY_NEW_GAIT){
    gaitSetup = &MyGaitSetup;
    gaitGen = &MyGaitGenerator;
    gaitLegNo[RIGHT_FRONT] = 0;
    gaitLegNo[LEFT_FRONT] = 2;
    gaitLegNo[RIGHT_REAR] = 4;
    gaitLegNo[LEFT_REAR] = 6;
    pushSteps = 6;
    stepsInCycle = 8;
}
        

Your code must define:

Optionally, you may also define:

Other Hacking

TODO: add what values mean, out of range issues, etc

Under development in V2.0/SVN-LATEST is a new gait file format. Gait files (.gait) contain the following:

REQUIRES: leg 4 6
REQUIRES: ik lizard3 mammal3
GAIT:MY_GAIT_NAME 
gaitGen = &NewGaitGen;
gaitSetup = &DefaultGaitSetup;
gaitLegNo[RIGHT_FRONT] = 0;
gaitLegNo[LEFT_MIDDLE] = 0;
gaitLegNo[RIGHT_REAR] = 0;
gaitLegNo[LEFT_REAR] = 2;
gaitLegNo[LEFT_FRONT] = 2;
gaitLegNo[RIGHT_REAR] = 2;
pushSteps = 2;  
stepsInCycle = 4;     
GENERATOR: NewGaitGen, This is a new gait generator
if( MOVING ){ 
  ...
}
SETUP: NewGaitSetup, This is a new setup function
...
GLOBAL: variableIneed
        

The first line is a requirements statement, that this gait is only for 4 or 6 legged robots. The second line is an additional statement that this gait is only to be used for the mammal3 or lizard3 IK specifications.

Where MY_GAIT_NAME would be something like AMBLE_SMOOTH. This is followed by the actual gait generation code. We then have defined a GENERATOR, which has a name, and a description (which will be used as a comment), followed by the body of the function.

This file format will be used to generate the gaits.h file automatically.

Licensing

All of the ArbotiX code, libraries, and Arduino extensions are licensed under the GNU Lesser General Public License v2.1. PyPose, and any other desktop software included (such as PyMech), is released under the GNU General Public License v2.