Copter: integrate refs for RC_Channels in motor defs
This commit is contained in:
parent
8baf5ebf4a
commit
2b3995ccb5
@ -474,15 +474,15 @@ static struct {
|
||||
#endif
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME // helicopter constructor requires more arguments
|
||||
static MOTOR_CLASS motors(&g.rc_1, &g.rc_2, &g.rc_3, &g.rc_4, &g.rc_7, &g.rc_8, &g.heli_servo_1, &g.heli_servo_2, &g.heli_servo_3, &g.heli_servo_4);
|
||||
static MOTOR_CLASS motors(g.rc_1, g.rc_2, g.rc_3, g.rc_4, g.rc_7, g.rc_8, g.heli_servo_1, g.heli_servo_2, g.heli_servo_3, g.heli_servo_4);
|
||||
#elif FRAME_CONFIG == TRI_FRAME // tri constructor requires additional rc_7 argument to allow tail servo reversing
|
||||
static MOTOR_CLASS motors(&g.rc_1, &g.rc_2, &g.rc_3, &g.rc_4, &g.rc_7);
|
||||
static MOTOR_CLASS motors(g.rc_1, g.rc_2, g.rc_3, g.rc_4, g.rc_7);
|
||||
#elif FRAME_CONFIG == SINGLE_FRAME // single constructor requires extra servos for flaps
|
||||
static MOTOR_CLASS motors(&g.rc_1, &g.rc_2, &g.rc_3, &g.rc_4, &g.single_servo_1, &g.single_servo_2, &g.single_servo_3, &g.single_servo_4);
|
||||
static MOTOR_CLASS motors(g.rc_1, g.rc_2, g.rc_3, g.rc_4, g.single_servo_1, g.single_servo_2, g.single_servo_3, g.single_servo_4);
|
||||
#elif FRAME_CONFIG == COAX_FRAME // single constructor requires extra servos for flaps
|
||||
static MOTOR_CLASS motors(&g.rc_1, &g.rc_2, &g.rc_3, &g.rc_4, &g.single_servo_1, &g.single_servo_2);
|
||||
static MOTOR_CLASS motors(g.rc_1, g.rc_2, g.rc_3, g.rc_4, g.single_servo_1, g.single_servo_2);
|
||||
#else
|
||||
static MOTOR_CLASS motors(&g.rc_1, &g.rc_2, &g.rc_3, &g.rc_4);
|
||||
static MOTOR_CLASS motors(g.rc_1, g.rc_2, g.rc_3, g.rc_4);
|
||||
#endif
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
@ -686,12 +686,10 @@ static AP_InertialNav inertial_nav(&ahrs, &barometer, g_gps, gps_glitch);
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
AC_AttitudeControl_Heli attitude_control(ahrs, ins, aparm, motors, g.pi_stabilize_roll, g.pi_stabilize_pitch, g.pi_stabilize_yaw,
|
||||
g.pid_rate_roll, g.pid_rate_pitch, g.pid_rate_yaw,
|
||||
g.rc_1.servo_out, g.rc_2.servo_out, g.rc_4.servo_out, g.rc_3.servo_out);
|
||||
g.pid_rate_roll, g.pid_rate_pitch, g.pid_rate_yaw);
|
||||
#else
|
||||
AC_AttitudeControl attitude_control(ahrs, ins, aparm, motors, g.pi_stabilize_roll, g.pi_stabilize_pitch, g.pi_stabilize_yaw,
|
||||
g.pid_rate_roll, g.pid_rate_pitch, g.pid_rate_yaw,
|
||||
g.rc_1.servo_out, g.rc_2.servo_out, g.rc_4.servo_out, g.rc_3.servo_out);
|
||||
g.pid_rate_roll, g.pid_rate_pitch, g.pid_rate_yaw);
|
||||
#endif
|
||||
AC_PosControl pos_control(ahrs, inertial_nav, motors, attitude_control,
|
||||
g.pi_alt_hold, g.pid_throttle_rate, g.pid_throttle_accel,
|
||||
|
Loading…
Reference in New Issue
Block a user