ethz-asl / rotors_simulator

RotorS is a UAV gazebo simulator
1.22k stars 757 forks source link

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

Open TaoYibo1866 opened 4 years ago

TaoYibo1866 commented 4 years ago

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?

TYXDG commented 2 years ago

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_attitudegain)

TaoYibo1866 commented 2 years ago

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.

scarlett-sun commented 1 year ago

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

barrosiuri commented 7 months ago

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)?