Skip to content
This repository has been archived by the owner on Apr 6, 2020. It is now read-only.

Miscellaneous Information on Inertial Sensing

Jorhabib Eljaik edited this page Mar 30, 2016 · 4 revisions

Index


General info regarding inertial sensors

Distributed Inertial Sensing wiki:

More specific information about the hardware and installation of the distributed inertial sensors found in iCubGenova02 and other robots can be found in the following wiki: http://wiki.icub.org/wiki/Distributed_Inertial_sensing.

Understanding inertial ports data

The data found on ports like icub/right_leg/inertialMTB contains a series of data packages with the following structure:

a = (n  6.0  (a1  b1 t1 x1 y1 x1)   .... (an  bn tn xn yn xn))
ai = pos of sensor ... see enum type
bi = accel (1) or gyro (2)
tn = time stamp.
  • Typedef enum as sent by Marco Accame:
enum { eoas_inertial_pos_offsetleft = 0, eoas_inertial_pos_offsetright = 24, eoas_inertial_pos_offsetcentral = 48 };
/** @typedef    typedef enum eOas_inertial_position_t
    @brief      contains a unique id for every possible inertial sensor positioned on iCub. So far we can host up to 63 different positions. The actual positions on iCub are documented on http://wiki.icub.org/wiki/Distributed_Inertial_sensing where one must look for the tags 10B12, 10B13 etc. The mapping on CAN for the ETH robot v3 is written aside.  **/

typedef enum
{
    eoas_inertial_pos_none                  = 0, 

...
    // left leg
    eoas_inertial_pos_l_foot_1              = 8+eoas_inertial_pos_offsetleft,       // label 10B12  canloc = (CAN2, 13)
    eoas_inertial_pos_l_foot_2              = 9+eoas_inertial_pos_offsetleft,       // label 10B13  canloc = (CAN2, 12)
    eoas_inertial_pos_l_lower_leg_1         = 10+eoas_inertial_pos_offsetleft,      // label 10B8   canloc = (CAN2,  8)
    eoas_inertial_pos_l_lower_leg_2         = 11+eoas_inertial_pos_offsetleft,      // label 10B9   canloc = (CAN2,  9) 
    eoas_inertial_pos_l_lower_leg_3         = 12+eoas_inertial_pos_offsetleft,      // label 10B10  canloc = (CAN2, 10)
    eoas_inertial_pos_l_lower_leg_4         = 13+eoas_inertial_pos_offsetleft,      // label 10B11  canloc = (CAN2, 11)
    eoas_inertial_pos_l_upper_leg_1         = 14+eoas_inertial_pos_offsetleft,      // label 10B1   canloc = (CAN1,  1)
    eoas_inertial_pos_l_upper_leg_2         = 15+eoas_inertial_pos_offsetleft,      // label 10B2   canloc = (CAN1,  2)
    eoas_inertial_pos_l_upper_leg_3         = 16+eoas_inertial_pos_offsetleft,      // label 10B3   canloc = (CAN1,  3)
   eoas_inertial_pos_l_upper_leg_4         = 17+eoas_inertial_pos_offsetleft,      // label 10B4   canloc = (CAN1,  4)
    eoas_inertial_pos_l_upper_leg_5         = 18+eoas_inertial_pos_offsetleft,      // label 10B5   canloc = (CAN1,  5)
    eoas_inertial_pos_l_upper_leg_6         = 19+eoas_inertial_pos_offsetleft,      // label 10B6   canloc = (CAN1,  6)
    eoas_inertial_pos_l_upper_leg_7         = 20+eoas_inertial_pos_offsetleft,      // label 10B7   canloc = (CAN1,  7)

    // right leg
    eoas_inertial_pos_r_foot_1              = 8+eoas_inertial_pos_offsetright,      // label 11B12  canloc = (CAN2, 13)
    eoas_inertial_pos_r_foot_2              = 9+eoas_inertial_pos_offsetright,      // label 11B13  canloc = (CAN2, 12)
    eoas_inertial_pos_r_lower_leg_1         = 10+eoas_inertial_pos_offsetright,     // label 11B8   canloc = (CAN2,  8)
    eoas_inertial_pos_r_lower_leg_2         = 11+eoas_inertial_pos_offsetright,     // label 11B9   canloc = (CAN2,  9)
    eoas_inertial_pos_r_lower_leg_3         = 12+eoas_inertial_pos_offsetright,     // label 11B10  canloc = (CAN2, 10)
    eoas_inertial_pos_r_lower_leg_4         = 13+eoas_inertial_pos_offsetright,     // label 11B11  canloc = (CAN2, 11)
    eoas_inertial_pos_r_upper_leg_1         = 14+eoas_inertial_pos_offsetright,     // label 11B1   canloc = (CAN1,  1)
    eoas_inertial_pos_r_upper_leg_2         = 15+eoas_inertial_pos_offsetright,     // label 11B2   canloc = (CAN1,  2)
    eoas_inertial_pos_r_upper_leg_3         = 16+eoas_inertial_pos_offsetright,     // label 11B3   canloc = (CAN1,  3)
    eoas_inertial_pos_r_upper_leg_4         = 17+eoas_inertial_pos_offsetright,     // label 11B5   canloc = (CAN1,  5)
    eoas_inertial_pos_r_upper_leg_5         = 18+eoas_inertial_pos_offsetright,     // label 11B4   canloc = (CAN1,  4)
    eoas_inertial_pos_r_upper_leg_6         = 19+eoas_inertial_pos_offsetright,     // label 11B6   canloc = (CAN1,  6)
    eoas_inertial_pos_r_upper_leg_7         = 20+eoas_inertial_pos_offsetright,     // label 11B7   canloc = (CAN1,  7)
} eOas_inertial_position_t;

Using the XSens Yarp plugin

The XSens plugin in YARP can be used when attaching a single XSens IMU to your computer. It is as simple as adding to your yarp application the following module:

yarpdev --device inertial --subdevice xsensmtx --name /externalxsens/data:o

Where:

  • inertial is the C++ class yarp::dev::ServerInertial, a network wrapper.
  • xsensmtx is the compiled driver (library xsensmtx.so) which can be found $ICUB_DIR/lib/iCub/xsensmtx.so when enabled at compilation time through the flag ENABLE_icubmod_xsensmtx

Next, you will find a port called /externalxsens/data:o with a similar output to that of /inertial when using the real robot.

The format of the data provided through this port is as follows [4]: The output consists in 12 double, organized as follows:

  • Euler angles (3): deg
  • linear acceleration (3): m/s^2
  • angular speed (3): deg/s
  • magnetic field (3): arbitrary units

External Inertial Sensors for iCubGenova02

The temporary solution that has been found to be able to have a gyroscope somewhere in the foot along with an accelerometer, was to use a skin palm of the iCub and attach it on top of the F/T sensor of the right foot. The way how this works is by attaching this palm to one of the boards of the foot (There are currently two present with their own accelerometers that we are not using in this particular firmware mod). The ethernet robot has some differences with respect to the black robot as to how to add new hardware, mainly due to some intermediate element between the new sensor that you connect and the ethernet network. Marco Accame was kind enough to help me handle this issue, by compiling a specific version of the firmware that enables the streaming of the palm sensors (acc + gyro) to the ethernet. This means, however, that if a new firmware is loaded on the boards of the feet (or the whole robot), you must make sure that it's merged in the new firmware, and then load it manually. Let me describe how and where you can do this.

In PC104:

  1. cd into /usr/local/src/robot/icub-firmware-build/testing
  2. git pull to fetch the most recent version of our specific feet firmware.
  3. Make sure robotInterface is down! From a PC104 terminal launch ethLoader ↪️ Discover ↪️ Click on 10.0.1.10 (IP for right foot) and 10.0.1.11 ↪️ Click on Procs ↪️ check the last version is similar to the original one, e.g. current firmware version is 2.26, then ours will be 222.26. ↪️ click on Upload App ↪️ browse to .../icub-firmware-build/testing/ems-jorhabib ↪️ Click on Open.

At this point you have loaded a merged version (with what we need) of the most recent firmware only for the two feet.

Then, in order to enable the gyroscope from this board do the following:

In PC104

  1. cd into $ICUB_DIR/share/iCub/robots/iCubGenova02/hardware/skin
  2. Modify the file right_leg-ems11-inertial_mtb.xml and in the field param name = enabledGyroscopes put the corresponding board to which the palm is attached. Either r_foot_1 or r_foot_2

Now you're good to go and can proceed to start the robotInterface

Reverting to the previous firmware

It may happen that the custom build may interfere with the rest of the boards. If the firmware on the feet does not load, then sequentially, some others won't either. If you then want to revert to the previous version, this will be icub-firmware-build/EMS/bin/applications/ems.hex

The procedure is currently very cumbersome but this is seen by the firmware team as a temporary solution, on one hand because the feet boards should in the future contain also a gyroscope, on the other, because we still need to have something solid that we are actually using before introducing permanently these changes. An option that I suggested to Mr. Accame was to enable these options on the firmware from configuration file. He will look into this option after making some changes to the code and I will try to remind him, so that he doesn't have to compile a version for us every time the firmware changes.

Physical Installation

iCub's palm board is attached to foot as shown in the following picture:

Another important detail is in the wiring of the cables. This is the standard palm board that we are attaching to the MTB board:


References:

  1. Server Inertial C++ source code
  2. Yarp devices
  3. Documentation on class yarp::dev::ServerInertial
  4. MTX Inertial Sensor Output