rotors_simulator icon indicating copy to clipboard operation
rotors_simulator copied to clipboard

Implementation of angular_rate_error in roll_pitch_yawrate_thrust_controller.cpp does not match with the paper

Open TaoYibo1866 opened this issue 4 years ago • 4 comments

According to Control of complex maneuvers for a quadrotor UAV using geometric methods on SE(3) https://arxiv.org/pdf/1003.2005.pdf, the anglular rate error should be Eigen::Vector3d angular_rate_error = odometry_.angular_velocity - R.transpose() * R_des * angular_rate_des;. However, in https://github.com/ethz-asl/rotors_simulator/blob/master/rotors_control/src/library/roll_pitch_yawrate_thrust_controller.cpp line 111, the implementation is Eigen::Vector3d angular_rate_error = odometry_.angular_velocity - R_des.transpose() * R * angular_rate_des;. Is this a bug?

TaoYibo1866 avatar Apr 08 '20 09:04 TaoYibo1866

Hello, I have noticed the problem you mentioned. In addition, when calculating the expected angular acceleration in the computedesiredangularacc function, angular velocity is cross-multiplied by angular velocity, which is obviously an invalid operation. What do you think? Thank you very much!

*angular_acceleration = -1 * angle_error.cwiseProduct(normalized_attitude_gain_) - angular_rate_error.cwiseProduct(normalized_angular_rate_gain_) + odometry_.angular_velocity.cross(odometry_.angular_velocity);

TYXDG avatar Jul 05 '22 07:07 TYXDG

This cross-multiplication is valid, but always return zero. In this paper, there is

M = −kR * eR − kΩ * eΩ + Ω × JΩ

The code you mentioned just omitted J.

TaoYibo1866 avatar Jul 09 '22 16:07 TaoYibo1866

I also wonder why the controller for M omits the last part(the long expression) when it is easy to implement?

scarlett-sun avatar Mar 18 '23 14:03 scarlett-sun

Did you guys find out why did they omit the last part of the expression and why they are performing an operation that always returns zero (cross product with itself)?

barrosiuri avatar Jan 10 '24 01:01 barrosiuri