System Information
ReFlex hardware overview
ReFlex software overview
Tutorials
Support
Calibrate IMU
Note: Only the ReFlex TakkTile 2 hand has IMUs in the fingers.
Looking at raw IMU data
You can find all relevant IMU data on /hand_state topic. Once your hand is plugged in to power and your computer via ethernet, run the full reflex_takktile2 roslaunch file and echo the topic with the following command:
roslaunch reflex reflex_takktile2.launch
(in a new terminal)
rostopic echo /reflex_takktile2/hand_state
Note: When you see your_gripper or your_msgs in a command you will need to replace it with the command appropriate for the model of ReFlex gripper you are working with.


By echoing this topic, you can see all the data pertaining to the hand state. This includes the IMU data from the fingers and the palm. To look at only the IMU data in the fingers, or if the echo is going off the screen, try
rostopic echo /reflex_takktile2/hand_state/finger

The absolute orientation data from the IMU sensors are being streamed and read using quaternions. In the topic, these are labelled as quat. Euler angles are also provided, but it is important to note that they are just calculated and converted using the quaternion data in the python code.
Other important information includes the calibration status and the calibration data, which will be useful for the calibration process.
NOTE: Everytime the ReFlex TakkTile 2 Hand is powered on, the IMU must be calibrated to get relative orientation data. This can be achieved either through loading the calibration offset values or going through the manual calibration process.
Calibrating the IMU with Provided Values
If you are provided with calibration offset values in a finger_calibrate.yaml file or you have saved these values previously by following the manual calibration procedure (shown below), you can load the values into the ReFlex hand. If the roslaunch file has been run, you can call the /loadIMUCalData rosservice to load the values, provided that they are stored in the finger_calibrate.yaml file located in the directory: reflex-ros-pkg/reflex_driver2/yaml
rosservice call /reflex_takktile2/loadIMUCalData
The values of the calibration offsets will be displayed in the same terminal where the launch file was run.
The distal section of the fingers can be displayed using the visualizer to get a sense of the calibrated IMU sensors (the visualizer tutorial can be found here). The visualizer can provide an approximate orientation of the distals, but will display some inaccuracy due to noise from the sensors and reference frame of the palm IMU sensor. However, if the orientation is completely off, retry the loading process by power cycling the ReFlex hand and rotating the ReFlex Hand randomly before calling the /loadIMUCalData service again.
Manual Calibration Procedure
Given you have run the roslaunch file, you can proceed with manually calibrating the IMU sensors. It will be useful to echo the /hand_state topic and /hand_state/finger topic to display the calibration status while you are going through the procedure.
To calibrate the IMU sensors, you will be physically rotating the hand and moving it. There are a couple of steps that you will have to take. This is to calibrate the individual sensors inside the IMU, which include the accelerometer, gyroscope, and magnetometer. An IMU is fully calibrated when the calibration status is equal to 255. After a few seconds, the calibration offset registers will be read and displayed under calibration data.
For magnetometer calibration, make some random movements (such as moving the hand in a number ‘8’ fashion) for about 10 seconds.
For gyroscope calibration, place the ReFlex hand in a single stable position for a period of a few seconds to allow the gyroscope to calibrate.
For accelerometer calibration, place the ReFlex hand in 6 different stable positions for a period of few seconds each to allow the accelerometer to calibrate. Make sure that there is slow movement between 2 stable positions. The 6 stable positions could be in any direction, but make sure that the device is lying at least once perpendicular to the x, y and z axis. This may take multiple attempts.
When all calibration statuses read 255 and the calibration data has been outputted, you can call the rosservice /saveIMUCalData to save them into the current finger_calibrate.yaml file location in reflex-ros-pkg/reflex_driver2/yaml.
rosservice call /reflex_takktile2/saveIMUCalData
Afterwards, the manual procedure process does not have to be repeated and the values can now be loaded using the rosservice /loadIMUCalData.

