5 Setup a new head
5.1 Configure AttributeTree
5.1.1 Preconditions
In this chapter we assume that you have a working MCA and Head-Project installation. (Preferably tested with a already working head)
5.1.2 Preperation
The Attribute-Tree that configures the encoder and motor settings is located at: ~mca2.4/project/armar3/etc/can.AttributeTree
Changes to this file will only be applied after the dsp_control_part
is restarted using stopcans
and startcans
. As an alternative, mcabrowser
can be used to change the values in the corresponding group. Values changed with the browser have to be entered in the can.AttributeTree in order to be persistent.
Identify the secion of
can.AttributeTree
which corresponds to the joints that move in the wrong direction. The file is organized following the DSP ids from the CAN interface.Identify the motor id of the joint: Check the MappingTable entry in the section of AttributeTree corresponding to the joint. The first entries map each motor (A,B,C) to a joint name. Remember the motor id (A,B or C).
Assure that all
Set Joint Moving Direction
entries in the can.AttributeTree are set to0x0
.
5.1.3 Setup encoder count direction
A wrong encoder count direction will result in an incomplete reset procedure. In order to determine whether you are facing this problem, set the values Reset Offset
of the joint the behaves unexpected to 0.
Then reset the joint using the HEAD_COMMAND.mcagui
.
If the joint does not move towards the joint limit, the encoder direction is not correct. Change the encoder count direction by adjusting Revert Encoder Countdir
in the AttributeTree:
The revert encoder countdir bitmask is organized in the following way:
bit (LSB first) | 0 | 1 | 2 | 3 | 4 | 5 |
encoder | axis A | motor A | axis B | motor B | axis C | motor C |
If the joint does still not move during reset, increase the absolute value of the Reset PWM
setting of the corresponding joint, carefully. Too high PWM settings will damage the motor
5.1.4 Setup correct reset PWM direction
Invert the sign of Reset PWM
if one joint does not reset in the correct direction:
The joints should reset in the following directions (looking at the head from the front):
- neck pitch: front
- neck roll: right
- neck yaw: left
- neck tilt: up
- eye tilt: up
- left eye pan: left
- right eye pan: left
5.1.5 Setting up the reset offsets
Reset offsets move the joints to the initial position after the reset procedure reached the joint limit.
The direction of the reset offset is crucial for the initialization of the head.
Start with a low Reset Offset
setting in the AttributeTree (e.g. 500) and reset the joint. If the joint does not move away from the joint limit press the emergency stop. Afterwards invert the reset offset.
If the reset offset points to the correct direction, increase the value until the joint is in the desired initial position after reset.
5.1.6 Setting up joint limits
The joint limit settings are crucial to protect the head from hitting the limits and motor damage.
In order to setup the joint limits perform the following steps:
- Start and reset the head
- Press emergency stop
- Start
mcabrowser
and navigate tovirtual MainGroup
-><DSP-Head>
->DSP-Head
. Click onSensorOutput
and activateAuto-Update
. - Manually move each joint towards the joint limits to determine minimal and maximal joint positions for the joint.
- Use these settings (maybe a little bit lower) for the entry
_JOINTNAME_ Max Position
and_JOINTNAME_ Min Position
in the can.AttributeTree
5.2 Adapt angle to impuls factors
5.2.1 Preconditions
This section assumes that you have configured the Reset Encoder Coundir
, Set Joint Moving Direction
and Reset PWM
values as explained in the previous section.
Changes to be done in file: ~/mca2.4/project/armar3/action/control/Armar3Definitions.cpp
The changes will only be applied if project is recompiled and head is restarted.
5.2.2 Setup direction of angle2impuls
The angle2impuls values determine in which direction the joints will move when controlled from the robot_interface or from within the mcagui.
Start and reset the head.
Start the control gui with
mcagui HEAD_GUI.mcagui
Select
Direct Kinematics
,Execution Toggle
andHead Manual
Move each joint by using the sliders. If the sliders are moved in positive direction, the joints should move according to the followng table (looking at the head from the front):
Joint | Direction |
---|---|
neck pitch | down |
neck roll | left |
neck yaw | left |
neck tilt | down |
eye tilt | up |
eye left pan | right |
eye right pan | right |
- For each joint that moves in a different direction, invert the sign of corresponding angle2impuls factor in
Armar3Definitions.cpp
:
tDataType Armar3::angle2impuls_factors_head[] = {
302.22*RADIAN2DEGREE, // neck pitch
302.22*RADIAN2DEGREE, // neck roll
151.11*RADIAN2DEGREE, // neck yaw
311.0*RADIAN2DEGREE, // neck tilt
339.85*RADIAN2DEGREE, // eye tilt
-258.74*RADIAN2DEGREE, // eye pan left
-258.74*RADIAN2DEGREE // eye pan right
};
5.2.3 Calibrate Angle2Impuls factors
The procedure for angle2impuls calibration is explained here: FIXME.
5.3 Check movement directions
5.3.1 Preconditions
The head should be correctly setup as described in the previous sections, started and all joints reset.
5.3.2 Check joint directions
Start and reset the head.
Start the control gui
HEAD_GUI.mcagui
Select
Direct Kinematics
,Execution Toggle
andHead Manual
Move each joint by using the sliders. If the sliders are moved in positive direction, the joints should move according to the followng table (looking at the head from the front):
Joint | Direction |
---|---|
neck pitch | down |
neck roll | left |
neck yaw | left |
neck tilt | down |
eye tilt | up |
eye left pan | right |
eye right pan | right |
5.3.3 Check eyes
- Use kinematic mode
Inv. Kin (Only Eyes)
- Set 3D Coordinate Input to X=0, Y=250, Z=174. Eyes should look towards the “nose”, tilt should be straight.
- Increase the Y value. Eyes should look less towards the “nose”.
- Increase the Z value. Eyes should look up.
- Increase the X value. Eyes should look to the left (looking the head in the face).
5.3.4 Check neck pitch, tilt and yaw
- Use kinematic mode ‘’Inv. Kin (First 3 DOF)’’
- Set 3D Coordinate Input to X=0, Y=1000, Z=174. Eyes should look towards the “nose”, otherwise straight.
- Increase Z value to 300. Head should look up.
- Increase X value to 300. Head should look left (looking the head in the face).
5.4 Fixing the visualisation
5.4.1 Preconditions
The head is correctly setup as described in the previous sections.
5.4.2 Adapt model axis
In some cases, the direction of the joint movement in simulation and on the real head do not correspond.
For each joint that moves in a different direction in the visualization, the rotation axis has to be inverted. This is done in the file projects/armar3/etc/oi/head/armar3_head.iv
In the file there is en entry for each joint specifying the rotation axis:
DEF (JOINT_NAME) Transform {
rotation x y z 1
}
In order to invert the moving direction of one joint in visualization, invert the value of x,y or z (depending on the joint).
Restart the GUI in order to see the changes.