mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
ArduCopter Tri: fix for enable_out of yaw servo, defined yaw servo for APM2
This commit is contained in:
parent
64f59e4dd5
commit
1dcd50e3be
@ -49,8 +49,7 @@
|
||||
//
|
||||
//
|
||||
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
|
||||
/* TODO find out correct channel for APM2 TRI_YAW */
|
||||
# define CH_TRI_YAW (-1)
|
||||
# define CH_TRI_YAW CH_7
|
||||
#elif CONFIG_APM_HARDWARE == APM_HARDWARE_APM1
|
||||
# define CH_TRI_YAW CH_7
|
||||
#endif
|
||||
|
@ -13,6 +13,7 @@ static void motors_output_enable()
|
||||
APM_RC.enable_out(MOT_1);
|
||||
APM_RC.enable_out(MOT_2);
|
||||
APM_RC.enable_out(MOT_4);
|
||||
APM_RC.enable_out(CH_TRI_YAW);
|
||||
}
|
||||
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user