Browse Source

Fix for reversed pitch in SIMPLE mode.

git-svn-id: https://arducopter.googlecode.com/svn/trunk@1779 f9c3cf11-9bcb-44bc-f272-b75c42450872
master
jasonshort 14 years ago
parent
commit
94d34ad117
  1. 4
      ArduCopterMega/navigation.pde

4
ArduCopterMega/navigation.pde

@ -104,8 +104,8 @@ void calc_waypoint_nav() @@ -104,8 +104,8 @@ void calc_waypoint_nav()
//Serial.printf("X%2.4f, Y%2.4f ", cos_nav_x, sin_nav_y);
// rotate the vector
nav_roll = (float)nav_lat * cos_nav_x;
nav_pitch = (float)nav_lat * sin_nav_y;
nav_roll = (float)nav_lat * cos_nav_x;
nav_pitch = -(float)nav_lat * sin_nav_y;
//Serial.printf("R%ld, P%ld ", nav_roll, nav_pitch);

Loading…
Cancel
Save