mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
ArduCopter: changed sin_pitch and sin_roll to faster equivalents
This commit is contained in:
parent
a5feda6b1f
commit
b5c1e23549
@ -2165,8 +2165,8 @@ static void update_trig(void){
|
|||||||
cos_yaw_x = yawvector.y; // 0x = north
|
cos_yaw_x = yawvector.y; // 0x = north
|
||||||
|
|
||||||
// added to convert earth frame to body frame for rate controllers
|
// added to convert earth frame to body frame for rate controllers
|
||||||
sin_roll = sin(ahrs.roll);
|
sin_pitch = -temp.c.x;
|
||||||
sin_pitch = sin(ahrs.pitch);
|
sin_roll = temp.c.y / cos_pitch_x;
|
||||||
|
|
||||||
//flat:
|
//flat:
|
||||||
// 0 ° = cos_yaw: 0.00, sin_yaw: 1.00,
|
// 0 ° = cos_yaw: 0.00, sin_yaw: 1.00,
|
||||||
|
Loading…
Reference in New Issue
Block a user