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

Copter: reduce default AltHold P to 1.0 (was 2.0)

This helps reduce jumpiness due to althold feed forward
parent fbe166d8
No related branches found
No related tags found
No related merge requests found
...@@ -5,6 +5,7 @@ Improvements over 3.0.0-rc5 ...@@ -5,6 +5,7 @@ Improvements over 3.0.0-rc5
1) bug fix to Circle mode's start position (was moving to last loiter target) 1) bug fix to Circle mode's start position (was moving to last loiter target)
2) WP_ACCEL parameter added to allow user to adjust acceleration during missions 2) WP_ACCEL parameter added to allow user to adjust acceleration during missions
3) loiter acceleration set to half of LOIT_SPEED parameter value (was hard-coded) 3) loiter acceleration set to half of LOIT_SPEED parameter value (was hard-coded)
4) reduce AltHold P to 1.0 (was 2.0)
------------------------------------------------------------------ ------------------------------------------------------------------
ArduCopter 3.0.0-rc5 04-Jun-2013 ArduCopter 3.0.0-rc5 04-Jun-2013
Improvements over 3.0.0-rc4 Improvements over 3.0.0-rc4
......
...@@ -918,7 +918,7 @@ ...@@ -918,7 +918,7 @@
#endif #endif
#ifndef ALT_HOLD_P #ifndef ALT_HOLD_P
# define ALT_HOLD_P 2.0f # define ALT_HOLD_P 1.0f
#endif #endif
#ifndef ALT_HOLD_I #ifndef ALT_HOLD_I
# define ALT_HOLD_I 0.0f # define ALT_HOLD_I 0.0f
......
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