mirror of https://github.com/ArduPilot/ardupilot
Moved a camera mount function call, out of the servos update function
This commit is contained in:
parent
f4998c3673
commit
59cbb8ec6f
|
@ -730,6 +730,9 @@ static void slow_loop()
|
|||
|
||||
update_aux_servo_function();
|
||||
|
||||
#if CAMERA == ENABLED
|
||||
camera_mount.update_mount_type();
|
||||
#endif
|
||||
break;
|
||||
|
||||
case 2:
|
||||
|
|
|
@ -267,8 +267,4 @@ static void update_aux_servo_function()
|
|||
g_rc_function[aux_servo_function[CH_6]] = &g.rc_6;
|
||||
g_rc_function[aux_servo_function[CH_7]] = &g.rc_7;
|
||||
g_rc_function[aux_servo_function[CH_8]] = &g.rc_8;
|
||||
|
||||
#if CAMERA == ENABLED
|
||||
camera_mount.update_mount_type();
|
||||
#endif
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue