tu-darmstadt-ros-pkg / hector_gazebo

hector_gazebo provides packages related to the simulation of robots using gazebo (gazebo plugins, world files etc.).
http://www.ros.org/wiki/hector_gazebo
181 stars 155 forks source link

Question regarding IMU plugin #51

Closed JaFeKl closed 6 years ago

JaFeKl commented 6 years ago

Hello guys,

I recently took a closer look into your IMU plugin and I'm a little bit confused by the following lines of code:

`rate = this->offset_.rot.GetInverse()

shouldn't it be `rate = rot.GetInverse()

, since you want to rotate the calculated angular rate from the world into the body reference frame and not only rotate it by the "rpyOffset" value.

I would really appreciate your comments on that, maybe it's just an error in reasoning by myself :)

JaFeKl commented 6 years ago

or where else is the angular velocity rotated from world into the body frame? for the acceleartion it's clear to me by using rot.RotateVectorReverse() but I can't find any similiar term regarding the angular velocity...

meyerj commented 6 years ago

The body angular rate is derived from the two orientation quaternions at the current and the previous update step:

  math::Quaternion delta = this->orientation.GetInverse() * rot;
  this->orientation = rot;

delta is a quaternion which represents the orientation difference between two subsequent update steps. The rate vector is basically delta's equivalent rotation vector (or the vector part of the quaternion logarithm), divided by the time difference dt (first order approximation). delta is already expressed in body frame because of the order of the two operands and the result does not depend on the constant rotation offset applied in line 251.

The left-multiplication of this->offset_.rot.GetInverse() was added in https://github.com/tu-darmstadt-ros-pkg/hector_gazebo/commit/d5fcb4a40756559fb94cfbbfeae2abbc63bc5e34 in order to fix #23.

JaFeKl commented 6 years ago

Thank you very much for this! It really helped me in understand the code.