ArduCopter: Change TRI_FRAME yaw servo output to CH_TRI_YAW define

This commit is contained in:
Pat Hickey 2012-01-01 15:24:07 -05:00
parent ccff9041f8
commit b22920c0ea
2 changed files with 13 additions and 1 deletions

View File

@ -1130,7 +1130,7 @@ static void fifty_hz_loop()
#if FRAME_CONFIG == TRI_FRAME #if FRAME_CONFIG == TRI_FRAME
// servo Yaw // servo Yaw
g.rc_4.calc_pwm(); g.rc_4.calc_pwm();
APM_RC.OutputCh(CH_7, g.rc_4.radio_out); APM_RC.OutputCh(CH_TRI_YAW, g.rc_4.radio_out);
#endif #endif
} }

View File

@ -43,6 +43,18 @@
# define MOT_8 CH_11 # define MOT_8 CH_11
#endif #endif
//
//
// Output CH mapping for TRI_FRAME yaw servo
//
//
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
/* TODO find out correct channel for APM2 TRI_YAW */
# define CH_TRI_YAW (-1)
#elif CONFIG_APM_HARDWARE == APM_HARDWARE_APM1
# define CH_TRI_YAW CH_7
#endif
// //
// //
// Output CH mapping for Aux channels // Output CH mapping for Aux channels