diff --git a/ArduCopter/Attitude.pde b/ArduCopter/Attitude.pde index 0b210c5bebf17ddfe7aa81af467ab02011ef7903..b53b27ad87f4c47d3c08b10dc9b7869fbfd74c2e 100644 --- a/ArduCopter/Attitude.pde +++ b/ArduCopter/Attitude.pde @@ -409,9 +409,23 @@ get_nav_yaw_offset(int yaw_input, int reset) return ahrs.yaw_sensor; }else{ +#if ALTERNATIVE_YAW_MODE == ENABLED _yaw = nav_yaw + (yaw_input / 50); return wrap_360(_yaw); +#else + // re-define nav_yaw if we have stick input + if(yaw_input != 0){ + // set nav_yaw + or - the current location + _yaw = yaw_input + ahrs.yaw_sensor; + // we need to wrap our value so we can be 0 to 360 (*100) + return wrap_360(_yaw); + + }else{ + // no stick input, lets not change nav_yaw + return nav_yaw; } +#endif + } } static int16_t get_angle_boost(int16_t value) diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 6db23de2570e45eebc7d5791aae5b143ae208ace..89c6ecf00076b4eeb98a80c005e78bbf8d3510bf 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -989,4 +989,8 @@ # define RETRO_LOITER_MODE DISABLED #endif +#ifndef ALTERNATIVE_YAW_MODE +# define ALTERNATIVE_YAW_MODE DISABLED +#endif + #endif // __ARDUCOPTER_CONFIG_H__