Added warning, needs more work on the rotation matrix output

This commit is contained in:
Lorenz Meier 2013-01-09 16:56:23 +01:00
parent d60173224f
commit 1a107bd7bf
1 changed files with 2 additions and 0 deletions

View File

@ -413,6 +413,8 @@ int attitude_estimator_ekf_thread_main(int argc, char *argv[])
/* send out */
att.timestamp = raw.timestamp;
// XXX Apply the same transformation to the rotation matrix
att.roll = euler[0] - ekf_params.roll_off;
att.pitch = euler[1] - ekf_params.pitch_off;
att.yaw = euler[2] - ekf_params.yaw_off;