Page 1 of 1

MWC on 8MHz

Posted: Sat Feb 18, 2012 10:43 am
by remoteme
Hi !

I am addressing this to developers directy involved in MWC software development, who knows all the intimacies.
There is a chance to have such assignment soon, get it as a job, not a fancy hobby to trash when you see can't be done.
So it's do it, or fire me ...
The task is to make work the core of the mwc on a 8MHz 3.3V (wearable) machine. I don't want to hear it's impossible :) we must make it !
So far I identified the following possible approaches / facts:
- the simplest would be to force processor at 16MHz, but I am afraid can't be done... 168-10MU, single cell lipo power, requirements I can't change. Am I wrong and is this possible ?
- software changes: this is the way I want to go... how hard do you see it? Anything that can't be done at 8Mhz if all software timings are changed accordingly ? Giros only, no acc, baro or mag sensors should be supported. The partes affected seems to be ESC and servos timing logic, anything else ?

So, these are the cards, if anyone want to help me identifying all the places to change in MWC to make this possible, please PM me.
Of course discussions can continue here, not only PM.
Once done will post the sources as a branch of this project.

Thank you !

Re: MWC on 8MHz

Posted: Sat Feb 18, 2012 10:55 am
by timecop
Switch to STM8S, which runs in-spec at >= 3.0V at 16MHz.

Re: MWC on 8MHz

Posted: Sat Feb 18, 2012 11:20 am
by remoteme
Can't change hardware platform, sorry.
What so terrible to change timings at 8MHz? Servos 128 steps instead 256? Acceptable... ESC 244Hz refresh insetead 488? Even 50Hz are good !
Make me understand why avoiding 8MHz ?

Re: MWC on 8MHz

Posted: Sat Feb 18, 2012 1:47 pm
by Alexinparis
Hi,

I think it's possible.
As you said, it's just some tuning to do on the right timers.
The cycle time would be longer, but with a simple gyro config, it should run.

Re: MWC on 8MHz

Posted: Sat Feb 18, 2012 4:08 pm
by remoteme
Cycle time is in the 2700-3100 ballpark with the present hardware.

Re: MWC on 8MHz

Posted: Sat Feb 18, 2012 8:13 pm
by mr.rc-cam
the simplest would be to force processor at 16MHz, but I am afraid can't be done... 168-10MU, single cell lipo power, requirements I can't change. Am I wrong and is this possible ?

It sounds like you have decided to use the 8MHz CPU and will change the MWC code. However, if this does not work out then don't despair. Although it is not recommended in the datasheet, overclocking a 3.5V powered ATMEGA to 16MHz is low risk (other hobby projects have done it and it worked fine). So if you want to eliminate the software changes then just swap the xtal and try it out at 16MHz. However, the '168 may not have enough memory for a typical MWC (not impossible, but be careful of out-of-memory problems).

- Thomas

Re: MWC on 8MHz

Posted: Mon Feb 20, 2012 2:52 pm
by JohnyGab
Anyway, this guy here sale Arudnio Pro mini 3.3V 16mhz, ( He doesnt have read the spec ), and as I see, he never had any complain :P

Re: MWC on 8MHz

Posted: Wed Mar 07, 2012 8:58 pm
by kos
it is flying ... mutliwii with 328p @ 8mhz 3.3v

many thanks to the output rewrite . I had a hard time questioning the analogWrite function .

as i am unable to commit, here are the changes:

Sensors: the F_CPU macro that was not used for i2c

Code: Select all

### Eclipse Workspace Patch 1.0
#P trunk
Index: MultiWii_shared/Sensors.pde
===================================================================
--- MultiWii_shared/Sensors.pde   (révision 623)
+++ MultiWii_shared/Sensors.pde   (copie de travail)
@@ -120,7 +120,7 @@
     I2C_PULLUPS_DISABLE
   #endif
   TWSR = 0;                                    // no prescaler => prescaler = 1
-  TWBR = ((16000000L / I2C_SPEED) - 16) / 2;   // change the I2C clock rate
+  TWBR = ((F_CPU / I2C_SPEED) - 16) / 2;       // change the I2C clock rate
   TWCR = 1<<TWEN;                              // enable twi module, no interrupt
 }
 
@@ -450,7 +450,7 @@
 void Baro_update() {
   if (currentTime < bmp085_ctx.deadline) return;
   bmp085_ctx.deadline = currentTime;
-  TWBR = ((16000000L / 400000L) - 16) / 2; // change the I2C clock rate to 400kHz, BMP085 is ok with this speed
+  TWBR = ((F_CPU / 400000L) - 16) / 2; // change the I2C clock rate to 400kHz, BMP085 is ok with this speed
   switch (bmp085_ctx.state) {
     case 0:
       i2c_BMP085_UT_Start();
@@ -595,7 +595,7 @@
 void Baro_update() {
   if (currentTime < ms561101ba_ctx.deadline) return;
   ms561101ba_ctx.deadline = currentTime;
-  TWBR = ((16000000L / 400000L) - 16) / 2; // change the I2C clock rate to 400kHz, MS5611 is ok with this speed
+  TWBR = ((F_CPU / 400000L) - 16) / 2; // change the I2C clock rate to 400kHz, MS5611 is ok with this speed
   switch (ms561101ba_ctx.state) {
     case 0:
       i2c_MS561101BA_UT_Start();
@@ -630,7 +630,7 @@
 }
 
 void ACC_getADC () {
-  TWBR = ((16000000L / 400000L) - 16) / 2;
+  TWBR = ((F_CPU / 400000L) - 16) / 2;
   i2c_getSixRawADC(MMA7455_ADDRESS,0x00);
 
   ACC_ORIENTATION( ((int8_t(rawADC[1])<<8) | int8_t(rawADC[0])) ,
@@ -661,7 +661,7 @@
 }
 
 void ACC_getADC () {
-  TWBR = ((16000000L / 400000L) - 16) / 2; // change the I2C clock rate to 400kHz, ADXL435 is ok with this speed
+  TWBR = ((F_CPU / 400000L) - 16) / 2; // change the I2C clock rate to 400kHz, ADXL435 is ok with this speed
   i2c_getSixRawADC(ADXL345_ADDRESS,0x32);
 
   ACC_ORIENTATION( ((rawADC[1]<<8) | rawADC[0]) ,
@@ -717,7 +717,7 @@
 }
 
 void ACC_getADC () {
-  TWBR = ((16000000L / 400000L) - 16) / 2;  // Optional line.  Sensor is good for it in the spec.
+  TWBR = ((F_CPU / 400000L) - 16) / 2;  // Optional line.  Sensor is good for it in the spec.
   i2c_getSixRawADC(BMA180_ADDRESS,0x02);
   //usefull info is on the 14 bits  [2-15] bits  /4 => [0-13] bits  /4 => 12 bit resolution
   ACC_ORIENTATION( ((rawADC[1]<<8) | rawADC[0])/16 ,
@@ -758,7 +758,7 @@
 }
 
 void ACC_getADC(){
-  TWBR = ((16000000L / 400000L) - 16) / 2;
+  TWBR = ((F_CPU / 400000L) - 16) / 2;
   i2c_getSixRawADC(0x70,0x02);
   ACC_ORIENTATION( ((rawADC[1]<<8) | rawADC[0])/64 ,
                    ((rawADC[3]<<8) | rawADC[2])/64 ,
@@ -779,7 +779,7 @@
 }
 
 void ACC_getADC() {
-  TWBR = ((16000000L / I2C_SPEED) - 16) / 2; // change the I2C clock rate. !! you must check if the nunchuk is ok with this freq
+  TWBR = ((F_CPU / I2C_SPEED) - 16) / 2;// change the I2C clock rate. !! you must check if the nunchuk is ok with this freq
   i2c_getSixRawADC(0xA4,0x00);
 
   ACC_ORIENTATION(  ( (rawADC[3]<<2)        + ((rawADC[5]>>4)&0x2) ) ,
@@ -803,7 +803,7 @@
 }
 
 void i2c_ACC_getADC(){
-  TWBR = ((16000000L / 400000L) - 16) / 2; // change the I2C clock rate to 400kHz
+  TWBR = ((F_CPU / 400000L) - 16) / 2; // change the I2C clock rate to 400kHz
   i2c_getSixRawADC(LIS3A,0x28+0x80);
   ACC_ORIENTATION( ((rawADC[1]<<8) | rawADC[0])/4 ,
                    ((rawADC[3]<<8) | rawADC[2])/4 ,
@@ -827,7 +827,7 @@
 }
 
   void ACC_getADC () {
-  TWBR = ((16000000L / 400000L) - 16) / 2;
+  TWBR = ((F_CPU / 400000L) - 16) / 2;
   i2c_getSixRawADC(0x30,0xA8);
 
   ACC_ORIENTATION( ((rawADC[1]<<8) | rawADC[0])/16 ,
@@ -869,7 +869,7 @@
 }
 
 void Gyro_getADC () {
-  TWBR = ((16000000L / 400000L) - 16) / 2; // change the I2C clock rate to 400kHz
+  TWBR = ((F_CPU / 400000L) - 16) / 2; // change the I2C clock rate to 400kHz
   i2c_getSixRawADC(0XD2,0x80|0x28);
 
   GYRO_ORIENTATION( ((rawADC[1]<<8) | rawADC[0])/20  ,
@@ -904,7 +904,7 @@
 }
 
 void Gyro_getADC () {
-  TWBR = ((16000000L / 400000L) - 16) / 2; // change the I2C clock rate to 400kHz
+  TWBR = ((F_CPU / 400000L) - 16) / 2; // change the I2C clock rate to 400kHz
   i2c_getSixRawADC(ITG3200_ADDRESS,0X1D);
   GYRO_ORIENTATION( ((rawADC[0]<<8) | rawADC[1])/4 , // range: +/- 8192; +/- 2000 deg/sec
                     ((rawADC[2]<<8) | rawADC[3])/4 ,
@@ -928,7 +928,7 @@
   uint8_t axis;
   if ( currentTime < t ) return; //each read is spaced by 100ms
   t = currentTime + 100000;
-  TWBR = ((16000000L / 400000L) - 16) / 2; // change the I2C clock rate to 400kHz
+  TWBR = ((F_CPU / 400000L) - 16) / 2; // change the I2C clock rate to 400kHz
   Device_Mag_getADC();
   if (calibratingM == 1) {
     tCal = t;
@@ -1052,7 +1052,7 @@
 #if defined(MPU6050)
 
 void Gyro_init() {
-  TWBR = ((16000000L / 400000L) - 16) / 2; // change the I2C clock rate to 400kHz
+  TWBR = ((F_CPU / 400000L) - 16) / 2; // change the I2C clock rate to 400kHz
   i2c_writeReg(MPU6050_ADDRESS, 0x6B, 0x80);             //PWR_MGMT_1    -- DEVICE_RESET 1
   delay(5);
   i2c_writeReg(MPU6050_ADDRESS, 0x19, 0x00);             //SMPLRT_DIV    -- SMPLRT_DIV = 0  Sample Rate = Gyroscope Output Rate / (1 + SMPLRT_DIV)
@@ -1155,7 +1155,7 @@
 
 uint8_t WMP_getRawADC() {
   uint8_t axis;
-  TWBR = ((16000000L / I2C_SPEED) - 16) / 2; // change the I2C clock rate
+  TWBR = ((F_CPU / I2C_SPEED) - 16) / 2;// change the I2C clock rate
   i2c_getSixRawADC(0xA4,0x00);
 
   if (micros() < (neutralizeTime + NEUTRALIZE_DELAY)) {//we neutralize data in case of blocking+hard reset state
@@ -1198,4 +1198,4 @@
   if (BARO) Baro_init();
   if (MAG) Mag_init();
   if (ACC) {ACC_init();acc_25deg = acc_1G * 0.423;}
-}
+}
\ Pas de retour chariot à la fin du fichier


Output.pde
motor 3 , 11 : same as promini 16mhz , but prescaler to 32 instead of 64
motor 9 , 10 : same as promicro with top and value div 2 (because we are running x2 slower )

1 writemotors :

Code: Select all

#if defined(PROMINI8MHZ)
     #if (NUMBER_MOTOR > 0) // Timer 1 A & B [1000:2000] => [8000:16000]
      OCR1A = motor[0]<<2; //  pin 9
    #endif
    #if (NUMBER_MOTOR > 1)
      OCR1B = motor[1]<<2; //  pin 10
    #endif
    #if (NUMBER_MOTOR > 2)
      #ifndef EXT_MOTOR_RANGE
        OCR2A = motor[2]>>3; //  pin 11
      #else
        OCR2A = ((motor[2]>>2) - 250) + 2;
      #endif
    #endif
    #if (NUMBER_MOTOR > 3)
      #ifndef EXT_MOTOR_RANGE
        OCR2B = motor[3]>>3; //  pin 3
      #else
        OCR2B = ((motor[3]>>2) - 250) + 2;
      #endif
    #endif
    #if (NUMBER_MOTOR > 4) //note: EXT_MOTOR_RANGE not possible here
      atomicPWM_PIN6_highState = ((motor[4]-1000)>>2)+5;
      atomicPWM_PIN6_lowState  = 245-atomicPWM_PIN6_highState;
      atomicPWM_PIN5_highState = ((motor[5]-1000)>>2)+5;
      atomicPWM_PIN5_lowState  = 245-atomicPWM_PIN5_highState;
    #endif
    #if (NUMBER_MOTOR > 6) //note: EXT_MOTOR_RANGE not possible here
      atomicPWM_PINA2_highState = ((motor[6]-1000)>>2)+5;
      atomicPWM_PINA2_lowState  = 245-atomicPWM_PINA2_highState;
      atomicPWM_PIN12_highState = ((motor[7]-1000)>>2)+5;
      atomicPWM_PIN12_lowState  = 245-atomicPWM_PIN12_highState;
    #endif
  #endif



2 initOutput :

Code: Select all

 #if defined(PROMINI8MHZ)
       #if (NUMBER_MOTOR > 0)
   
    TCCR1A |= (1<<WGM11); TCCR1A &= ~(1<<WGM10); TCCR1B |= (1<<WGM13);  // phase correct mode
      TCCR1B &= ~(1<<CS11); ICR1 |= 0x2000; // no prescaler & TOP to 16383;
      TCCR1A |= _BV(COM1A1); // connect pin 9 to timer 1 channel A
    #endif
    #if (NUMBER_MOTOR > 1)
      TCCR1A |= _BV(COM1B1); // connect pin 10 to timer 1 channel B
    #endif
    #if (NUMBER_MOTOR > 2)
      TCCR2A |= _BV(COM2A1) | _BV(CS21) | _BV(CS20); // connect pin 11 to timer 2 channel A prescale32
    #endif
    #if (NUMBER_MOTOR > 3)
      TCCR2A |= _BV(COM2B1) ; // connect pin 3 to timer 2 channel B
    #endif
    #if (NUMBER_MOTOR > 5)  // PIN 5 & 6 or A0 & A1
      initializeSoftPWM();
      #if defined(A0_A1_PIN_HEX) || (NUMBER_MOTOR > 6)
        pinMode(5,INPUT);pinMode(6,INPUT);     // we reactivate the INPUT affectation for these two PINs
        pinMode(A0,OUTPUT);pinMode(A1,OUTPUT);
      #endif
    #endif
  #endif



done :
serial - ok
timer 1 timer 2 - ok
quad - ok

to do
:
servo - untested
sowtpwm - untested
tri / hex / octo - untested

here is the video of the first flight with multiwii 328p 8mhz : https://vimeo.com/37910708

here is the cycle time , ftdi usb connected and motor armed

Re: MWC on 8MHz

Posted: Thu Mar 08, 2012 3:56 pm
by kos
remoteme wrote:The task is to make work the core of the mwc on a 8MHz 3.3V (wearable) machine. I don't want to hear it's impossible :)
[..]
168-10MU, single cell lipo power, requirements I can't change. Am I wrong and is this possible ?
- software changes: this is the way I want to go... how hard do you see it? Anything that can't be done at 8Mhz if all software timings are changed accordingly


not that hard , with multiwii 2.0 and the above code an ATmega 168 @8mhz should fly as fine as an ATmega 328 @8mhz ;)

Re: MWC on 8MHz

Posted: Tue Mar 13, 2012 6:54 pm
by kos
hi ,

some additional changes in the code , now you can upload to a 8mhz board without any change in the config file

Code: Select all

 #if defined(PROMINI)
 
    #if (F_CPU > 8000000)
          #if (NUMBER_MOTOR > 0)
              blablabla ...



edit : delete "MultiWii_2_0_preversion3.zip"

Re: MWC on 8MHz

Posted: Wed Apr 25, 2012 4:04 am
by kos
tested again with a 10dof from drotek , cycletime is ~4300, no noticeable impact while flying

here is the latest news for 8mhz/3.3v support : everything is working
  • servo, guimbal ok

  • hex and octo ok


patched files :
  • output : adjust timer/counter based on F_CPU

  • sensors : i2c freq calculation based on F_CPU


no need to configure anything , just select the correct board in the arduino ide

Re: MWC on 8MHz

Posted: Tue May 01, 2012 9:39 am
by gicks
I was wondering if a 3.3V arduino Pro Mini will be able to power the WM+ module with its 3.3V. I'm not sure since my parts have not arrived yet. Anybody an idea if it is possible to run the WM+ and NK on 3.3v?

cheers,
gicks

Re: MWC on 8MHz

Posted: Tue May 01, 2012 9:53 am
by Tommie
Well, since WM+ and Nunchuk are usually connected to a Wiimote with two AA batteries...

I'm powering my WM+ with (roughly) 3.3V (5V dropped through 2 diodes), it's working flawlessly, actually, powering it with 5V is actually out of spec.

Re: MWC on 8MHz

Posted: Thu May 03, 2012 12:16 am
by gicks
The set-up is working now, great! Still have a small problem though. In the GUI the main graph is working fine, but the roll and pitch visuals do not work.

So I figured I might have to define what type of sensor I'm using. But in the the config.h file I can see all sorts of boards and sensors but which one describes the use of just the WMP? I basically have no idea were to define that I am using a WMP as gyro sensor. Anybody know what to do?

Re: MWC on 8MHz

Posted: Thu May 03, 2012 7:49 am
by kos
for the roll and pitch visuals : you need an accelerometer

Re: MWC on 8MHz

Posted: Sun Jul 22, 2012 2:10 am
by treym

Re: MWC on 8MHz

Posted: Sun Aug 19, 2012 10:30 pm
by edge0xc
hey,
i want to build a small FC for 1S and so i want to use 8mhz.
is it possible to run it with the internal osc.? or should i better use an external 8 mhz osc?
thanks,
Alex