mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 22:18:29 -04:00
Open up constraint on Rate Yaw Output for all copters.
This commit is contained in:
parent
abb6eb2471
commit
7eae382a22
@ -253,15 +253,9 @@ get_rate_yaw(int32_t target_rate)
|
|||||||
|
|
||||||
output = p+i+d;
|
output = p+i+d;
|
||||||
|
|
||||||
// output control:
|
|
||||||
#if FRAME_CONFIG == HELI_FRAME
|
|
||||||
int16_t yaw_limit = 4500;
|
|
||||||
#else
|
|
||||||
int16_t yaw_limit = 1400 + abs(g.rc_4.control_in);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// constrain output
|
// constrain output
|
||||||
output = constrain(output, -yaw_limit, yaw_limit);
|
output = constrain(output, -4500, 4500);
|
||||||
|
|
||||||
#if LOGGING_ENABLED == ENABLED
|
#if LOGGING_ENABLED == ENABLED
|
||||||
static int8_t log_counter = 0; // used to slow down logging of PID values to dataflash
|
static int8_t log_counter = 0; // used to slow down logging of PID values to dataflash
|
||||||
|
Loading…
Reference in New Issue
Block a user