by cosa » Sat Jul 12, 2008 10:20 pm
by cosa
Sat Jul 12, 2008 10:20 pm
Thanks for reply cosa, I’ve been working on your bioloid control for the last few days but don’t seen I get a hang on it. I am not a good programmer so I think it would be best if you could show me some step- by-step examples on how to generate some walking gaits, tune parameters etc. Many Thanks.
This is how you generate walking gaits:
0. Get the newest version (
http://sourceforge.net/project/showfile ... _id=225495)
1. Start the viewer.exe and bioloid.exe (you don't have to connect your robot)
# in the bioloid.exe terminal:
2. Type 'setparam' (without the ''), you'll see 200 parameters in the format id: value
3. To change the value of the parameter with id x to the value y use 'setparam x y', f.e. 'setparam 0 0.5' will change the first parameter to 0.5
4. Type 'test 0.05 5 0 0.1 0' to generate a walking gait. The first parameter is the forward/backward speed (examples: 0.06, 0.02), the second is the number of steps / 2, the third is the left/right speed (sidesteps, examples: 0.001, 0.005), the fourth parameter is the rotational speed (curves, examples: 0.2, 0.1, 0.05) and the fifth parameter is the storage number for the walking gait. If you don't supply a storage number the motion will be stored in 0 and played automatically (with interpolation type 13 = linear interpolation in joint space without collision checking and without generation of transition motions. You shouldn't use this with the real robot but it's good to test motions).
5. Play the gait in the visualizer with 'play 0 80 0' (see help, the first parameter is the storage number)
6. If you type 's 0 datei' the motion will be stored in a file named datei.xml in main/motions.
To understand what the parameters do you'll have to read the code and have a look at the paper
http://www.informatik.uni-freiburg.de/~ ... cra06.html
The code is very dirty at the moment: You'll find it in main/src/test.cpp. The main function is calcAngles. The parameters (see setparam) can be used via global.parameters[id] (global.parameters[0] is the value of the first parameter). The function will be called for left arm and left leg and right arm and right leg separately (take a look at void CTest::humanoidWalk(float* params, int paramcount)). The calculated joint values will be stored in angles[]. angles[0..5] is the leg starting at the first hip joint ending with the foot tilt joint, angles[6..8] is the arm starting at the first shoulder joint.
calcAngles:
Most of the code (especially the first part) is a direct translation of the algorithm mentioned in the paper. For example the vector aRobot is a_Robot in the paper, so aRobot.y is a_Robot^y.
I've added a few extra parameters to change a bunch of parameters at once.
There's interesting stuff at the end of the algorithm, where the angles[] are calculated. These are tweaks to adapt the kinematic structure used in the paper to the bioloid kinematic structure.
Some interesting parameters (I can remember):
3: determines how far the leg swings away from the center position during swinging
9: modifies the leg shortening during swinging
31: max. shortening length of the leg (in %)
32: leg length (in %)
58: max roll angle of the foot during swinging (if the foot rolls too much it will touch the ground)
56,57: extra pitch angle for the foot during swinging (to lift the heel)
33: global extra pitch angle for the hip (to keep balance)
34: global extra pitch angle for the foot (to keep balance)
Have fun. Please share your results with us and ask if you have any questions.
Thanks for reply cosa, I’ve been working on your bioloid control for the last few days but don’t seen I get a hang on it. I am not a good programmer so I think it would be best if you could show me some step- by-step examples on how to generate some walking gaits, tune parameters etc. Many Thanks.
This is how you generate walking gaits:
0. Get the newest version (
http://sourceforge.net/project/showfile ... _id=225495)
1. Start the viewer.exe and bioloid.exe (you don't have to connect your robot)
# in the bioloid.exe terminal:
2. Type 'setparam' (without the ''), you'll see 200 parameters in the format id: value
3. To change the value of the parameter with id x to the value y use 'setparam x y', f.e. 'setparam 0 0.5' will change the first parameter to 0.5
4. Type 'test 0.05 5 0 0.1 0' to generate a walking gait. The first parameter is the forward/backward speed (examples: 0.06, 0.02), the second is the number of steps / 2, the third is the left/right speed (sidesteps, examples: 0.001, 0.005), the fourth parameter is the rotational speed (curves, examples: 0.2, 0.1, 0.05) and the fifth parameter is the storage number for the walking gait. If you don't supply a storage number the motion will be stored in 0 and played automatically (with interpolation type 13 = linear interpolation in joint space without collision checking and without generation of transition motions. You shouldn't use this with the real robot but it's good to test motions).
5. Play the gait in the visualizer with 'play 0 80 0' (see help, the first parameter is the storage number)
6. If you type 's 0 datei' the motion will be stored in a file named datei.xml in main/motions.
To understand what the parameters do you'll have to read the code and have a look at the paper
http://www.informatik.uni-freiburg.de/~ ... cra06.html
The code is very dirty at the moment: You'll find it in main/src/test.cpp. The main function is calcAngles. The parameters (see setparam) can be used via global.parameters[id] (global.parameters[0] is the value of the first parameter). The function will be called for left arm and left leg and right arm and right leg separately (take a look at void CTest::humanoidWalk(float* params, int paramcount)). The calculated joint values will be stored in angles[]. angles[0..5] is the leg starting at the first hip joint ending with the foot tilt joint, angles[6..8] is the arm starting at the first shoulder joint.
calcAngles:
Most of the code (especially the first part) is a direct translation of the algorithm mentioned in the paper. For example the vector aRobot is a_Robot in the paper, so aRobot.y is a_Robot^y.
I've added a few extra parameters to change a bunch of parameters at once.
There's interesting stuff at the end of the algorithm, where the angles[] are calculated. These are tweaks to adapt the kinematic structure used in the paper to the bioloid kinematic structure.
Some interesting parameters (I can remember):
3: determines how far the leg swings away from the center position during swinging
9: modifies the leg shortening during swinging
31: max. shortening length of the leg (in %)
32: leg length (in %)
58: max roll angle of the foot during swinging (if the foot rolls too much it will touch the ground)
56,57: extra pitch angle for the foot during swinging (to lift the heel)
33: global extra pitch angle for the hip (to keep balance)
34: global extra pitch angle for the foot (to keep balance)
Have fun. Please share your results with us and ask if you have any questions.