Being not acquainted with Wii I ordered by mistake a WII RemotePlus. It is serial BGW22-4 dated 2010-07-22. I also ordered a first Nck, not finding anything looking like and ACC on it. I discovered the thing I needed was a Motion Plus and not a Remote Plus. So I got one of the clone Motion Plus with 2 Invenses classic Gyros on it. The second Nck was not working. So I ordered another one. Bad luck! Not working either. But, on the Wii Remote there is a nice ADXL335! By the way the two Nck were equipped with a MMA6631 and MMA7660. Useless as one is only 2 axis and the other is analog ACC outperformed by the ADXL335.
I used the ADXL335 on analog input A1-A2-A3 and it works. But I suspected a problem. Here it is:
Due to 3.3V for ADXL335, the reading of the values is not correct. I adapted some code from Sparkfun and modified the MWII soft that way:
After multiple test, I came back to original vlaues for ADC ACC as I had too much sensitivity. Vibration were more important than usable signal. So the original code for ADCACC in Sensors.pde is the one valid. Main change is is config.h where orientation is corrected, the chip being oriented as per datasheet, so here in config.h :
Code: Select all
/* ADC accelerometer */
//for 5DOF from sparkfun, uses analog PIN A1/A2/A3 - by uncommenting this you loose CAMSTAB
//#define ADCACC
#define ADXL335 //Added to adjust and scale up analog output of ADXL335 as it is on 3.3V
//if you want to change to orientation of individual sensor
#define ACC_ORIENTATION(X, Y, Z) {accADC[ROLL] = Y; accADC[PITCH] = -X; accADC[YAW] = Z;}
//#define GYRO_ORIENTATION(X, Y, Z) {gyroADC[ROLL] = -Y; gyroADC[PITCH] = X; gyroADC[YAW] = Z;}
//#define MAG_ORIENTATION(X, Y, Z) {magADC[ROLL] = X; magADC[PITCH] = Y; magADC[YAW] = Z;}
in def.h :
Code: Select all
#if defined(ADXL335) || defined(ADXL345) || defined(BMA020) || defined(BMA180) || defined(NUNCHACK) || defined(ADCACC)
#define ACC 1
#else
#define ACC 0
#endif
a line to change if needed the CMPF FACTOR only for ADX335 without touching other ADCACCs in IMU.pde :
Code: Select all
/* Set the Gyro Weight for Gyro/Acc complementary filter */
/* Increasing this value would reduce and delay Acc influence on the output of the filter*/
/* Default WMC value: 300/ previous value 310.0f*/
#if defined (ADXL335)
#define GYR_CMPF_FACTOR 310.0f
#else
#define GYR_CMPF_FACTOR 310.0f
#endif
in Sensors.pde before ADCACC:
Code: Select all
// ************************************************************************************************************
// ADXL335 ACC was a try to get more sensitivity, useless too much noise and vibrations & already cared for in the original code.
// ************************************************************************************************************
// ************************************************************************************************************
// ADC ACC
// ************************************************************************************************************
#if defined (ADCACC) || defined (ADXL335)
void ACC_init(){
pinMode(A1,INPUT);
pinMode(A2,INPUT);
pinMode(A3,INPUT);
acc_1G = 426; //acc_1G is the value of ACCZ when the multi is perfectly flat.
}
void ACC_getADC() {
ACC_ORIENTATION( -analogRead(A1) ,
-analogRead(A2) ,
analogRead(A3) );
ACC_Common();
}
#endif
It gives normal ACC reading on the GUI and efficient in LEVEL Mode.
Regards