Hi,
I'm using a CRIUS AIO PRO board in Y6, with servo on roll/pitch for camstab.
Since r1384 servos doesn't work, possible caused by a BUG. /They are even not holding, so the outputs are not activated/
I use them in HW-PWM mode.
Could anybody confirm?
BR
Adrian
HW PWM servo, BUG in r1384??
Re: HW PWM servo, BUG in r1384??
Right, camstab servos not work if camtrig is disabled.
Fixed in r1388.
Fixed in r1388.
Re: HW PWM servo, BUG in r1384??
Mis wrote:Right, camstab servos not work if camtrig is disabled.
Fixed in r1388.
After 1388, only roll servo works, pitch doesn't.
It seems like some BUG still exist...
Re: HW PWM servo, BUG in r1384??
Double check your connections and configuration. With r1388, CAMSTAB enabled, AIO PRO, and Y6 selected, both pitch and roll servos work (at pin 44,45), can be controlled via AUX channels and react to stabilisation.
Re: HW PWM servo, BUG in r1384??
Mis wrote:Double check your connections and configuration. With r1388, CAMSTAB enabled, AIO PRO, and Y6 selected, both pitch and roll servos work (at pin 44,45), can be controlled via AUX channels and react to stabilisation.
Hi, wiring was not changed since r1383. If I upload the 1383, both servos works, if I upload the r1388, only ROLL...
Anyway, I tried to find the difference in output.ino, and figured out that pinmode setup is missing here compared to the previous output.ino:
Code: Select all
#if (PRI_SERVO_TO >= 1) || (SEC_SERVO_TO >= 1)
TCCR5A |= (1<<WGM51); // phase correct mode & prescaler to 8 = 1us resolution
TCCR5A &= ~(1<<WGM50);
TCCR5B &= ~(1<<WGM52) & ~(1<<CS50) & ~(1<<CS52);
TCCR5B |= (1<<WGM53) | (1<<CS51);
ICR5 = SERVO_TOP_VAL;
#if (PRI_SERVO_FROM == 1 || SEC_SERVO_FROM == 1)
TCCR5A |= (1<<COM5C1); // pin 44
#endif
#if (PRI_SERVO_FROM <= 2 && PRI_SERVO_TO >= 2) || (SEC_SERVO_FROM <= 2 && SEC_SERVO_TO >= 2)
TCCR5A |= (1<<COM5B1); // pin 45
#endif
So I inserted them again like this:
Code: Select all
#if (PRI_SERVO_TO >= 1) || (SEC_SERVO_TO >= 1)
TCCR5A |= (1<<WGM51); // phase correct mode & prescaler to 8 = 1us resolution
TCCR5A &= ~(1<<WGM50);
TCCR5B &= ~(1<<WGM52) & ~(1<<CS50) & ~(1<<CS52);
TCCR5B |= (1<<WGM53) | (1<<CS51);
pinMode(44,OUTPUT);
ICR5 = SERVO_TOP_VAL;
#if (PRI_SERVO_FROM == 1 || SEC_SERVO_FROM == 1)
TCCR5A |= (1<<COM5C1); // pin 44
pinMode(45,OUTPUT);
#endif
#if (PRI_SERVO_FROM <= 2 && PRI_SERVO_TO >= 2) || (SEC_SERVO_FROM <= 2 && SEC_SERVO_TO >= 2)
TCCR5A |= (1<<COM5B1); // pin 45
pinMode(46,OUTPUT);
#endif
With this modification, both servos works again, with r1388.
I suggest to recheck and rethink this part in the r1388, maybe pinmodes should set up for every 8 servos...
BR
Adrian