Skip to content
Snippets Groups Projects
Commit aa8e5b0a authored by Randy Mackay's avatar Randy Mackay
Browse files

Copter: constrain auto roll and pitch to 45 degrees

parent e3628445
No related branches found
No related tags found
No related merge requests found
......@@ -592,6 +592,10 @@ static void calc_nav_pitch_roll()
// flip pitch because forward is negative
auto_pitch = -auto_pitch;
// constrain maximum roll and pitch angles to 45 degrees
auto_roll = constrain(auto_roll, -4500, 4500);
auto_pitch = constrain(auto_pitch, -4500, 4500);
}
static int16_t get_desired_speed(int16_t max_speed)
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment