[ Main Page ]

Arduino 6-axis IMU SD logger

Arduinoが出てから、SDカードやI2CやSPIセンサをかなり手軽に扱えるようになったと思う。これ以前であればPICで暗号のようなコードを書いて作るしかなかったので、 かなりの進歩だろう。センサは基本表面実装部品なので、変換基板かモジュールでないと扱いにくいが、加速度センサのADXL345やジャイロセンサのL3GD20はモジュールが広く販売されているので、 簡易的な慣性計測装置(IMU)としては使いやすい。CSV出力よりバイナリ出力の方が2倍程度高速な記録ができる。下記は、SDカードのルートにCFG.TXTとして一行目にサンプリングレート(ms)、 二行目に計測サンプル数を保存してから電源を入れるとその分だけ記録するようなコードである。記録中はLED点滅をするようにしている。CSV出力かバイナリ出力は コンパイル時に決めるようにしているが、もう少し手を入れればCFG.TXTで選択できるようにも出来るだろう。

表面、SDカード、センサ

裏面、I2Cレベル変換

Source

	#include <SdFat.h>
	#include <I2C.h>
	#include <TimerOne.h>

	// CSV writer
	#define ENABLE_CSV
	// debug serial output
	// #define FREERAM

	// pinout (acc,gyr:I2C) SDA=A4 SCL=A5 (SDcard:SPI) CS=4 SCK=D13 MISO=D12 MOSI=11
	// internal Timer1 PWM D9/D10
	// not used Timer0 PWM millis() D5/D6 Timer2 D3 D11
	// green LED D7
	// red LED D3

	#define LED_GREEN (7)
	#define LED_RED   (3)

	#define SDCARD_CS (4)
	#define ADXL345 (0x53)
	#define ADXL345_IDCO 0x00
	#define ADXL345_RATE 0x2C
	#define ADXL345_RATE_100HZ 0x0A
	#define ADXL345_RATE_200HZ 0x0B
	#define ADXL345_RATE_400HZ 0x0C
	#define ADXL345_RATE_800HZ 0x0D
	#define ADXL345_POWR 0x2D
	#define ADXL345_FORM 0x31
	#define ADXL345_FIFO_CTL 0x38

	#define L3GD20 B1101010  // SA0 = GND
	//const byte L3GD20 = B1101011;// SA0 = VDD_IO
	#define L3GD20_WHOAMI 0x0f
	#define L3GD20_CTRL1 0x20

	int32_t REC_COUNT = 200;
	int32_t SAMPLE_RATE_INTERVAL = 5000;
	// 5ms=200Hz 10ms=100Hz 2.5ms=400Hz 1.25ms=800Hz 0.5ms=2kHz

	#ifdef ENABLE_CSV
	bool CSVMODE = false;
	#endif

	// size must be < 255
	#ifdef ENABLE_CSV
	#define ACC_M_SIZE 50
	#else
	#define ACC_M_SIZE 60
	#endif

	// CSV 30[min] ~8Mbyte
	// CSV writer 200Hz -> 50
	// CSV writer 400Hz -> drop frame+
	// BIN writer 500Hz -> 60
	// BIN writer 800Hz -> 60 drop?
	// BIN writer 1kHz -> 60 ~drop+
	int16_t  _gyr[ACC_M_SIZE][3];
	int16_t  _acc[ACC_M_SIZE][3];

	//File accFile;
	SdFat SD;
	SdFile accFile;
	#ifdef FREERAM
	volatile int16_t _ram;
	#endif
	volatile uint8_t _acc_count8, _int_count8, _int_count8_hb;
	volatile uint16_t _acc_ret;
	volatile unsigned long time1, time2;

	void readRegister(int deviceAddress, int address, volatile int * to)
	{
	  I2c.read(deviceAddress, address, 0x6);
	  to[0] = I2c.receive(), to[0] |= I2c.receive() << 8;
	  to[1] = I2c.receive(), to[1] |= I2c.receive() << 8;
	  to[2] = I2c.receive(), to[2] |= I2c.receive() << 8;
	}

	void initAcc()
	{
	  I2c.read(ADXL345, ADXL345_IDCO, 1);
	  _acc_ret = I2c.receive() << 8;
	  I2c.write(ADXL345, ADXL345_RATE, ADXL345_RATE_200HZ);
	  I2c.write(ADXL345, ADXL345_FORM, B00001111); // LEFT-JUSTTIFIED FULL_RES 16G
	  I2c.write(ADXL345, ADXL345_FIFO_CTL, 0x00);
	  I2c.write(ADXL345, ADXL345_POWR, 0x00);
	  I2c.write(ADXL345, ADXL345_POWR, 0x10);
	  I2c.write(ADXL345, ADXL345_POWR, 0x08);

	  I2c.read(L3GD20, L3GD20_WHOAMI, 1);
	  _acc_ret |= I2c.receive();
	  //Serial.print("ADXL345(E5)L3GD2(D4):");
	  //Serial.println(_acc_count,HEX);//
	  I2c.write(L3GD20, L3GD20_CTRL1, B01111111);
	                              //   |||||||+ X axis enable
	                              //   ||||||+- Y axis enable
	                              //   |||||+-- Z axis enable
	                              //   ||||+--- PD: 0: power down, 1: active
	                              //   ||++---- BW1-BW0: cut off 70[Hz]:11 / 25:11
	                              //   ++------ DR1-DR0: ODR 190[HZ]:01 / 95:00
	}

	void measureAcc()
	{
	  int16_t acc[3];
	#ifdef FREERAM
	  if(_ram < freeRam()) _ram = freeRam();
	#endif
	  readRegister(ADXL345, 0x32, acc);
	  _acc[_acc_count8][0] = acc[0], _acc[_acc_count8][1] = acc[1], _acc[_acc_count8][2] = acc[2];
	  readRegister(L3GD20, 0x28|0x80, acc);
	  _gyr[_acc_count8][0] = acc[0], _gyr[_acc_count8][1] = acc[1], _gyr[_acc_count8][2] = acc[2];

	  // for DEBUG
	  // _acc[_acc_count][0] = -32768, _acc[_acc_count][1] = -32768, _acc[_acc_count][2] = -32768;
	  // _gyr[_acc_count][0] = -32768, _gyr[_acc_count][1] = -32768, _gyr[_acc_count][2] = -32768;
	  
	  _acc_count8 ++;
	  if(_acc_count8 == ACC_M_SIZE/2) {
	    _int_count8 ++;
	    if(_int_count8 == 0) _int_count8_hb ++;
	  }
	  else if(_acc_count8 == ACC_M_SIZE) {
	    _int_count8 ++;
	    if(_int_count8 == 0) _int_count8_hb ++;
	    _acc_count8 = 0;
	  }
	}

	#ifdef FREERAM
	int freeRam()
	{
	  extern int __heap_start, *__brkval;
	  int v;
	  return (int) &v - (__brkval == 0 ? (int) &__heap_start : (int) __brkval);
	}
	#endif
	    
	void setup()
	{
	  pinMode(LED_GREEN, OUTPUT);
	  pinMode(LED_RED,   OUTPUT);
	  digitalWrite(LED_GREEN, LOW);
	  digitalWrite(LED_RED,   LOW);
	  digitalWrite(LED_GREEN, HIGH);
	  digitalWrite(LED_RED,   HIGH);
	  delay(1000);
	#ifdef FREERAM
	  Serial.begin(9600);
	#endif
	  I2c.begin();
	  I2c.setSpeed(1);
	  while(1) {
	    initAcc();
	    if(0xE5D4 == _acc_ret) break;
	#ifdef FREERAM            
	    Serial.println("SensorError");
	#endif
	  }
	  digitalWrite(LED_GREEN, LOW);
	  pinMode(10, OUTPUT);
	  while(1) {
	    //if (!SD.begin(SDCARD_CS)) { delay(500); }
	    //if (!SD.begin(SDCARD_CS, SPI_FULL_SPEED)) {
	    if (!SD.begin(SDCARD_CS, SPI_HALF_SPEED)) {
	#ifdef FREERAM            
	      Serial.println("SDError");
	#endif
	      delay(100);
	      digitalWrite(LED_RED,   LOW);
	      delay(500);
	      digitalWrite(LED_RED,   HIGH);
	    }
	    else break;
	  }
	  digitalWrite(LED_RED,   LOW);
	  //Serial.println("OK");
	  delay(500);
	#ifdef FREERAM
	  _ram = 0;
	#endif
	  _acc_count8 =  _int_count8 = _int_count8_hb = 0;

	  // first line : fs
	  // second line : seconds
	  // third line : bin(0) or csv(1)
	  //if(!(accFile = SD.open("DATA.CFG", FILE_READ))) {
	  accFile.open("CFG.TXT", O_READ);
	  if(!accFile.isOpen()) {
	    //Serial.println("NOCFG");
	  } else {
	    char line[25] = {""};
	    int n;
	    if(accFile.fgets(line, sizeof(line)) > 0) {
	      SAMPLE_RATE_INTERVAL = 1000000L / atol(line);
	    }
	    if(accFile.fgets(line, sizeof(line)) > 0) {
	      REC_COUNT = 1000000L / SAMPLE_RATE_INTERVAL * atol(line) / ((long)ACC_M_SIZE / 2L) + 1L;
	    }
	#ifdef ENABLE_CSV
	    if(accFile.fgets(line, sizeof(line)) > 0) {
	      if(atoi(line) > 0) CSVMODE = true;
	    }
	#endif
	    accFile.close();
	  }
	  
	  //Serial.print("FS:");Serial.println(1000000L/SAMPLE_RATE_INTERVAL);
	  //Serial.print("Count:");Serial.println(REC_COUNT);
	  
	  SD.remove("DATA.LOG");
	  //accFile = SD.open("DATA.LOG", FILE_WRITE);
	  accFile.open("DATA.LOG", O_CREAT | O_APPEND | O_WRITE);
	  accFile.print("FS:");accFile.println(1000000L/SAMPLE_RATE_INTERVAL);
	  //accFile.print("FS(us):");accFile.println(SAMPLE_RATE_INTERVAL);
	  accFile.print("ISize:");accFile.println(ACC_M_SIZE/2);
	  accFile.print("I:");accFile.println(2); // acc+gyr
	  accFile.print("XYZ:");accFile.println(3);
	  accFile.print("Byte:");accFile.println(2);
	  accFile.print("Count:");accFile.println(REC_COUNT);
	  accFile.close();

	  SD.remove("DATA.CSV");
	  SD.remove("DATA.BIN");
	#ifdef ENABLE_CSV
	  if(CSVMODE) {
	    accFile.open("DATA.CSV", O_CREAT | O_WRITE);
	  } else {
	#endif
	    accFile.open("DATA.BIN", O_CREAT | O_WRITE);
	#ifdef ENABLE_CSV
	  }
	#endif
	  delay(500);
	  time1 = millis();
	  Timer1.initialize();
	  Timer1.attachInterrupt(measureAcc, SAMPLE_RATE_INTERVAL);
	}

	void loop()
	{
	  uint8_t _int_count8_copy = 0, _int_count8_hb_copy = 0, _pre_count8 = 0, _pre_count8_hb = 0;
	  uint32_t _int_count_copy = 0, _drop_count = 0;
	#ifdef FREERAM
	  uint32_t _main_loop_count = 0;
	  Serial.println("loop():");
	#endif

	  while(1) {
	    _int_count8_copy = _int_count8;
	#ifdef FREERAM
	    _main_loop_count ++;
	#endif
	    if(_int_count8_copy == _pre_count8) continue;
	    else {
	      if(((uint16_t)_int_count8_copy - (uint16_t)_pre_count8) == 1) {
	        _int_count_copy ++;
	      } else if((_int_count8_copy == 0)&&(_pre_count8 == 255)) {
	        _int_count_copy ++;
	      } else {
	        _drop_count ++;
	#ifdef FREERAM
	        Serial.println("@");
	#endif
	      }
	      _pre_count8 = _int_count8_copy;
	    }
	    
	    _int_count8_hb_copy = _int_count8_hb;
	    if((_int_count8_hb_copy - _pre_count8_hb) >= 2) {
	      _drop_count ++;
	#ifdef FREERAM
	      Serial.println("*");
	#endif
	    }
	    _pre_count8_hb = _int_count8_hb_copy;
	    
	    if(_int_count_copy < REC_COUNT+1) {
	#ifdef FREERAM            
	      Serial.print(_main_loop_count);
	      Serial.print("w");
	      Serial.print(_int_count_copy);
	      Serial.print("/");
	      Serial.print(REC_COUNT+1);
	      _main_loop_count = 0;
	#endif

	#ifdef ENABLE_CSV
	      if(CSVMODE) {
	        int count, count_max;
	          if(_int_count_copy & 1) { count = 0; count_max = ACC_M_SIZE/2; }
	          else { count = ACC_M_SIZE/2; count_max = ACC_M_SIZE; }
	          for(;count < count_max;count ++) {
	            //String line = "";
	            //line += String(_acc[cc][0],DEC) + String(",") + String(_acc[cc][1],DEC) + String(",") + String(_acc[cc][2],DEC) + String(",");
	            //line += String(_gyr[cc][0],DEC) + String(",") + String(_gyr[cc][1],DEC) + String(",") + String(_gyr[cc][2],DEC);
	            //accFile.println(line);
	            // 16bit integer -32768/32767 6x6digit+\0+5 commas = 42~3
	            char line[43];
	            sprintf(line, "%d,%d,%d,%d,%d,%d", _acc[count][0], _acc[count][1], _acc[count][2], _gyr[count][0], _gyr[count][1], _gyr[count][2]);
	            accFile.println(line);
	#ifdef FREERAM
	            if(_ram < freeRam()) _ram = freeRam();
	#endif
	          }
	      } else {
	#endif
	        uint8_t* __at;
	        __at = (uint8_t*)_acc;
	        if(_int_count_copy & 0x1 == 0) __at += sizeof(int)*3*ACC_M_SIZE/2;
	        accFile.write((uint8_t*)_acc,sizeof(int)*3*ACC_M_SIZE/2);
	        __at = (uint8_t*)_gyr;
	        if(_int_count_copy & 0x1 == 0) __at += sizeof(int)*3*ACC_M_SIZE/2;
	        accFile.write((uint8_t*)_gyr,sizeof(int)*3*ACC_M_SIZE/2);
	#ifdef FREERAM            
	        if(_ram < freeRam()) _ram = freeRam();
	#endif
	#ifdef ENABLE_CSV
	      }
	#endif

	#ifdef FREERAM
	      Serial.print(":");
	      Serial.print(_ram);
	      Serial.println("]");
	#endif
	      if(_pre_count8 & 0x1) {
	        digitalWrite(LED_GREEN, HIGH);
	      } else {
	        digitalWrite(LED_GREEN, LOW);
	      }
	      if(_drop_count > 0) {
	        digitalWrite(LED_RED,   HIGH);
	      }
	    } else {
	      time2 = millis();
	#ifdef FREERAM
	      Serial.print(_main_loop_count);Serial.print("c");Serial.println(_int_count_copy);
	      Serial.print("Drop:");Serial.println(_drop_count);
	      _main_loop_count = 0;
	#endif
	      accFile.close();
	      
	      accFile.open("DATA.LOG", O_APPEND | O_WRITE);
	      accFile.print("Drop:");accFile.println(_drop_count);
	      accFile.print("MS:");accFile.println(time2-time1);
	      accFile.print("SMPL:");accFile.println((long)REC_COUNT*(long)ACC_M_SIZE/(long)2);
	      accFile.close();
	      if(_drop_count > 0) {
	        digitalWrite(LED_RED,   HIGH);
	      }
	      Timer1.detachInterrupt();
	      while(1) {
	        digitalWrite(LED_GREEN, HIGH);
	        delay(1600);
	        digitalWrite(LED_GREEN, LOW);
	        delay(200);
	      }
	    }
	  } // while(1)
	}
      
There is no IGLU Cabal! Its members spent a better time of their lives writing
an RDBM server in a purely functional programming language. After having to
deal with designing many FP-friendly algorithms, and dealing with ugly code
that was made uglier due to FP, they found the task of maintaining the IGLU
site too mundande and unchallenging.

Shlomi Fish in Hackers-IL message No. 1964

    -- Shlomi Fish
    -- Hackers-IL Message No. 1964 ( http://tech.groups.yahoo.com/group/hackers-il/message/1964 )

Recently, Richard Stallman gave a speech in which he illustrated an academic
point about programming history by quoting a guy who described vi as 'an
editor spread at sword-point and which is really hard to use'.

I think I speak for all moderate vi(m) users when I say -- DEATH and DAMNATION
(in that order) to this Cardinal of the CTRL key! Needless to say my own local
vim user group has dispatched assassins to kill Mr. Stallman, but this is
hardly the end of the story. The fact is that a man has referred to another
man who in turn expressed some often-voiced reservations about OUR EDITOR! On
behalf of all editors of text everywhere, I implore EMACS users to return to
the true path, lest you be burned at the stake and then go to hell, the Buffer
From Which There Is No Unloading. We'll see how productive you are then, with
your ctrl-meta-alt and your ELISP and your 'ring buffer', whatever THAT is.

Peace and love to all.
^C
^X
quit
q
QUIT
exit :exit
zz
ZZ

kahei on
[Slashdot](http://linux.slashdot.org/comments.pl?sid=196931&cid=16136657)

    -- kahei
    -- Slashdot Comment ( http://linux.slashdot.org/comments.pl?sid=196931&cid=16136657 )


Powered by UNIX fortune(6)
[ Main Page ]