compass.set_declination(ToRad((2.0f * g.rc_6.control_in - g.radio_tuning_high)/100.0f), false); // 2nd parameter is false because we do not want to save to eeprom because this would have a performance impact
pid_log_counter++; // Note: get_rate_pitch pid logging relies on this function to update pid_log_counter so if you change the line above you must change the equivalent line in get_rate_pitch
#define CH6_STABILIZE_KP 1 // stabilize roll/pitch angle controller's P term
#define CH6_STABILIZE_KI 2 // stabilize roll/pitch angle controller's I term
#define CH6_STABILIZE_KD 29 // stabilize roll/pitch angle controller's D term
#define CH6_YAW_KP 3 // stabilize yaw heading controller's P term
#define CH6_YAW_KI 24 // stabilize yaw heading controller's P term
#define CH6_ACRO_KP 25 // acro controller's P term. converts pilot input to a desired roll, pitch or yaw rate
#define CH6_RATE_KP 4 // body frame roll/pitch rate controller's P term
#define CH6_RATE_KI 5 // body frame roll/pitch rate controller's I term
#define CH6_RATE_KD 21 // body frame roll/pitch rate controller's D term
#define CH6_YAW_RATE_KP 6 // body frame yaw rate controller's P term
#define CH6_YAW_RATE_KD 26 // body frame yaw rate controller's D term
#define CH6_THR_HOLD_KP 14 // altitude hold controller's P term (alt error to desired rate)
#define CH6_THROTTLE_KP 7 // throttle rate controller's P term (desired rate to acceleration or motor output)
#define CH6_THROTTLE_KI 33 // throttle rate controller's I term (desired rate to acceleration or motor output)
#define CH6_THROTTLE_KD 37 // throttle rate controller's D term (desired rate to acceleration or motor output)
#define CH6_THR_ACCEL_KP 34 // accel based throttle controller's P term
#define CH6_THR_ACCEL_KI 35 // accel based throttle controller's I term
#define CH6_THR_ACCEL_KD 36 // accel based throttle controller's D term
#define CH6_RELAY 9 // switch relay on if ch6 high, off if low
#define CH6_WP_SPEED 10 // maximum speed to next way point (0 to 10m/s)
#define CH6_LOITER_KP 12 // loiter distance controller's P term (position error to speed)
#define CH6_LOITER_KI 27 // loiter distance controller's I term (position error to speed)
#define CH6_HELI_EXTERNAL_GYRO 13 // TradHeli specific external tail gyro gain
#define CH6_OPTFLOW_KP 17 // optical flow loiter controller's P term (position error to tilt angle)
#define CH6_OPTFLOW_KI 18 // optical flow loiter controller's I term (position error to tilt angle)
#define CH6_OPTFLOW_KD 19 // optical flow loiter controller's D term (position error to tilt angle)
#define CH6_LOITER_RATE_KP 22 // loiter rate controller's P term (speed error to tilt angle)
#define CH6_LOITER_RATE_KI 28 // loiter rate controller's I term (speed error to tilt angle)
#define CH6_LOITER_RATE_KD 23 // loiter rate controller's D term (speed error to tilt angle)
#define CH6_AHRS_YAW_KP 30 // ahrs's compass effect on yaw angle (0 = very low, 1 = very high)
#define CH6_AHRS_KP 31 // accelerometer effect on roll/pitch angle (0=low)
#define CH6_INAV_TC 32 // inertial navigation baro/accel and gps/accel time constant (1.5 = strong baro/gps correction on accel estimatehas very strong does not correct accel estimate, 7 = very weak correction)
#define CH6_DECLINATION 38 // compass declination in radians
#define CH6_CIRCLE_RATE 39 // circle turn rate in degrees (hard coded to about 45 degrees in either direction)
#define CH6_NONE 0 // no tuning performed
#define CH6_STABILIZE_ROLL_PITCH_KP 1 // stabilize roll/pitch angle controller's P term
#define CH6_RATE_ROLL_PITCH_KP 4 // body frame roll/pitch rate controller's P term
#define CH6_RATE_ROLL_PITCH_KI 5 // body frame roll/pitch rate controller's I term
#define CH6_RATE_ROLL_PITCH_KD 21 // body frame roll/pitch rate controller's D term
#define CH6_STABILIZE_YAW_KP 3 // stabilize yaw heading controller's P term
#define CH6_YAW_RATE_KP 6 // body frame yaw rate controller's P term
#define CH6_YAW_RATE_KD 26 // body frame yaw rate controller's D term
#define CH6_ALTITUDE_HOLD_KP 14 // altitude hold controller's P term (alt error to desired rate)
#define CH6_THROTTLE_RATE_KP 7 // throttle rate controller's P term (desired rate to acceleration or motor output)
#define CH6_THROTTLE_RATE_KD 37 // throttle rate controller's D term (desired rate to acceleration or motor output)
#define CH6_THROTTLE_ACCEL_KP 34 // accel based throttle controller's P term
#define CH6_THROTTLE_ACCEL_KI 35 // accel based throttle controller's I term
#define CH6_THROTTLE_ACCEL_KD 36 // accel based throttle controller's D term
#define CH6_LOITER_POSITION_KP 12 // loiter distance controller's P term (position error to speed)
#define CH6_LOITER_RATE_KP 22 // loiter rate controller's P term (speed error to tilt angle)
#define CH6_LOITER_RATE_KI 28 // loiter rate controller's I term (speed error to tilt angle)
#define CH6_LOITER_RATE_KD 23 // loiter rate controller's D term (speed error to tilt angle)
#define CH6_WP_SPEED 10 // maximum speed to next way point (0 to 10m/s)
#define CH6_ACRO_KP 25 // acro controller's P term. converts pilot input to a desired roll, pitch or yaw rate
#define CH6_RELAY 9 // switch relay on if ch6 high, off if low
#define CH6_HELI_EXTERNAL_GYRO 13 // TradHeli specific external tail gyro gain
#define CH6_OPTFLOW_KP 17 // optical flow loiter controller's P term (position error to tilt angle)
#define CH6_OPTFLOW_KI 18 // optical flow loiter controller's I term (position error to tilt angle)
#define CH6_OPTFLOW_KD 19 // optical flow loiter controller's D term (position error to tilt angle)
#define CH6_AHRS_YAW_KP 30 // ahrs's compass effect on yaw angle (0 = very low, 1 = very high)
#define CH6_AHRS_KP 31 // accelerometer effect on roll/pitch angle (0=low)
#define CH6_INAV_TC 32 // inertial navigation baro/accel and gps/accel time constant (1.5 = strong baro/gps correction on accel estimatehas very strong does not correct accel estimate, 7 = very weak correction)
#define CH6_DECLINATION 38 // compass declination in radians
#define CH6_CIRCLE_RATE 39 // circle turn rate in degrees (hard coded to about 45 degrees in either direction)
// Commands - Note that APM now uses a subset of the MAVLink protocol