Manual PWM Output for dimmed light

Hi Everybody,

I am new to arducopter, I have a nicely flying DIY-Quadcopter which I just recently pimped with a few LEDs. They are very bright, so I would like to dim them a bit using PWM. I just didnt find any way to do this in the mission planner or elsewhere, so I think I have to program this manually in the user hookup functions.
I have done a lot of µC programming, so C++ is not a problem for me. Still I dont know the Arducopter program structure very well yet.

I tried the following code in the User Hook (after enableing the userhook in the config file)

void userhook_init()
{
hal_mpng.rcout->enable_ch(CH_11);
hal_mpng.rcout->set_freq(_BV(CH_11), 400);
hal_mpng.rcout->write(CH_11, (uint16_t)200);
}

But this does not result in any Output on the pin. Is there somebody with experience on user hook programming? Any help would be appreciated.

Thanks,

Michael

Just program the PWM yourself. See the Atmel reference manual for the ATmega1280/2560. Since you have uController experience, this should be no problem! here is some sample code:
void StopPWM(void)
{
TCCR2A=0;
}
void StartPWM(void)
{
// Use internal clock (datasheet p.160)
ASSR &= ~(_BV(EXCLK) | _BV(AS2));
//fixed on pin 11 and 12
//pinMode(12,OUTPUT);
// pinMode(speakerPin, OUTPUT); //OC1A

TCCR1A = _BV(COM1A0) | _BV(COM1B0) |_BV(WGM11)| _BV(WGM10);
TCCR1B = _BV(WGM13) | _BV(CS11);  // /8      // no prescaling ( div by 1 )

 // Set initial pulse width to the first sample.
OCR1A = 1000;

}
However, since you are into the code, you might try just a simple on off of the port bit and a software timer using the 100hz loop in ArduCopter. It wouldn’t be PWM, but it would still dim the LED.
Good luck!

[quote=“tbrkfd1”]Just program the PWM yourself. See the Atmel reference manual for the ATmega1280/2560. Since you have uController experience, this should be no problem! here is some sample code:
void StopPWM(void)
{
TCCR2A=0;
}
void StartPWM(void)
{
// Use internal clock (datasheet p.160)
ASSR &= ~(_BV(EXCLK) | _BV(AS2));
//fixed on pin 11 and 12
//pinMode(12,OUTPUT);
// pinMode(speakerPin, OUTPUT); //OC1A

TCCR1A = _BV(COM1A0) | _BV(COM1B0) |_BV(WGM11)| _BV(WGM10);
TCCR1B = _BV(WGM13) | _BV(CS11);  // /8      // no prescaling ( div by 1 )

 // Set initial pulse width to the first sample.
OCR1A = 1000;

}
However, since you are into the code, you might try just a simple on off of the port bit and a software timer using the 100hz loop in ArduCopter. It wouldn’t be PWM, but it would still dim the LED.
Good luck![/quote]

Hi tbrkfd1,
thanks for your reply. Did you use this code on an arducopter? I actually thought about doing it myself manually, but I am not sure which timers are used by the rest of the software already, and I dont want to corrupt the normal stuff. Also I never found a schematic of my board (Crius AIO), so I am not 100% sure about the pin configs. This is why I thought using the ARM PWM functions should make it much easier, because the board can handle 8 Motors -> 8 PWM outputs, of which 4 of them are not used.

Michael

I just got it working, actually it is quite simple once you know how to do it:

void userhook_init()
{

  hal_mpng.rcout->enable_ch(CH_8);

  hal_mpng.rcout->write(CH_8, (uint16_t)400);
  

}
#endif




#ifdef USERHOOK_MEDIUMLOOP
void userhook_MediumLoop()
{
  int16_t licht_kanal = hal_mpng.rcin->read(CH_6)-1000;
  
  if(licht_kanal < 0) licht_kanal = 0;
  if(licht_kanal > 1000) licht_kanal = 1000;
  
  float licht = licht_kanal;

  licht = licht*licht;
  licht /= 1000;  
  licht *= 2.3f;

    hal_mpng.rcout->write(CH_8, (uint16_t)licht);

  
}
#endif

in addition, you have to modify the RCOutput file and there specificly the write-function to remove the period-constrain for the PWM output channel (we want PWM to start from 0%) :

[code][code]void MPNGRCOutput::write(uint8_t ch, uint16_t period_us) {
/* constrain, then scale from 1us resolution (input units)

  • to 0.5us (timer units) */

uint16_t pwm;
if(ch != CH_8)
pwm = constrain_period(period_us) << 1;
else
pwm = period_us <<1;

switch(ch)
{
	case 0:  OCR3A = pwm; break; //5
	case 1:  OCR4A = pwm; break; //6
	case 2:  OCR3B = pwm; break; //2
	case 3:  OCR3C = pwm; break; //3
	case 4:  OCR5C = pwm; break; //5
	case 5:  OCR5B = pwm; break; //6
	case 6:  OCR4B = pwm; break; //7
	case 7:  OCR4C = pwm; break; //8
	case 9:  OCR1A = pwm; break; //10
	case 10: OCR1B = pwm; break; //11
}

}[/code][/code]