2017년 4월 7일 금요일

Linux device driver programming using some sensors

최근에 초등생 아들 녀석과 아두이노로 Line tracer를 만들어 보았다. Line tracer를 만들기 위해서는 아두이노(UNO) 외에도 초음파 거리 센서(장애물 감지), 적외선 센서(라인 센서), 조도 센서(터널 통과시 LED on), 서보 모터, 모터 드라이버 등이 필요하다.

아두이노 Line Tracer

이번 posting에서는 아두이노가 아닌 UDOO Neo 보드에 앞서 언급한 몇가지 센서(추가로 UDOO Neo에서 제공하는 3가지 모션 센서 포함)를 연결하는 시험을 진행해 보고자 한다. 이를 위해서는 wiringPi 같은 library나 python code를 사용하여 user space에서 구현하는 것이 훨씬 수월하겠으나, 본 고에서는 kernel programmer를 위하여 device driver를 이용한 접근 방법을 소개해 보고자 한다.

UDOO Neo board + some sensors + device drivers


<목차>
1. Target Board 및 시험 환경
2. 초음파 거리센서(HC-SR04)
3. 적외선 라인 Tracking 센서(FC-03)
4. 조도센서(HS-CDSM)
5. 3가지 모션(motion) 센서: accelerometer, magnetometer, gyroscope


1. Target Board 및 시험 환경
개발 환경(UDOO Neo 보드 및 buildroot)과 관련해서는 아래 posting의 내용 중 1절을 참조해 주기 바란다(반복되는 내용이라 생략함).
2. 초음파 거리센서(HC-SR04)
산 정상에 올라 "야호"하고 외칠때 울리는 메아리처럼, 초음파 센서는 소리가 벽 등의 물체에 부딛쳐 반사되어 돌아오는데 걸리는 시간을 측정하는 장치이다(사람의 귀에 들리지 않을 정도로 높은 주파수 -약 20 KHz 이상- 의 소리인 초음파가 가지고 있는 특성을 이용한 센서). 소리의 전달 속도가 340 m/s라는 사실을 이용한다면, 초음파 센서를 이용해 쉽게 거리 계산이 가능함을 알 수 있다.

아래 그림 2.1은 초음파 센서 중 비교적 저렴한 HC-SR04의 외관을 보여주는데, Vcc(5V), Trig, Echo 및 GND 등 모두 4개의 pin이 사용되고 있음을 알 수 있다. 이 중, Trig(Trigger) pin은 소리 전송 시작을 알리는 용도(GPIO output, Trig LOW -> HIGH -> LOW)로 사용되며, Echo  pin은 소리가 반사되어 돌아오는데 걸리는 시간을 측정하는 용도(GPIO input, Echo HIGH -> LOW 되기까지 걸리는 시간 측정)로 사용된다.

그림 2.1 HC-SR04 초음파 거리 센서

한가지 주의할 점은 HC-SR04의 Echo pin에서는 5V의 출력이 나오는데 반해, UDOO Neo 보드의 GPIO는 3.3V(참고: 아두이노는 5V임)를 사용한다는 사실이다. 따라서 회로 구성 시, 반드시 5V (입력) -> 3.3V로 분배(그림 2.2 ~ 2.3 참조)될 수 있도록 신경을 써 주어야 한다(이렇게 하지 않을 경우, 보드가 망가질 수도 있으니 주의하기 바란다).


그림 2.2 Voltage Divider(5V -> 3.3V)

그림 2.3 전압 분배 공식

위의 그림 2.2 ~ 2.3의 전압 분배 공식에 의하면 R1을 1K오옴, R2를 2K오옴으로 구성할 경우, Vin(5V)이 Vout(3.3V)로 분배될 수 있다.

Vout = 5 x 2000/(1000+2000) = 10/3 = 3.33333...

따라서 이를 토대로 할 때, 아래 그림 2.4와 같은 회로구성이 가능할 것으로 보인다.

그림 2.4 HC-SR04 연결도(좌측에 UDOO Neo 보드가 있다고 가정)

그림 2.5는 UDOO Neo 보드의 external pin 배치도이다. 이중에서 HC-SR04의 Trig 및 Echo pin과 external pin 중 어떤 pin을 연결하는 것이 적절할지 결정해야 한다(결과론이지만, 이중 우측 J4의 GPIO 180, 181 pin을 각각 Echo pin과 Trig pin에 연결하였다).

그림 2.5 UDOO Neo 보드 external pinouts

그림 2.6은 실제로 UDOO Neo 보드에 bread board를 이용하여 HC-SR04  초음파 거리 센서를 연결한 모습을 보여준다(참고로, 2K 저항이 없는 관계로 1K 저항 3개를 직렬로 연결하였음).

그림 2.6 UDOO Neo 보드에 HC-SR04 초음파 거리 센서 연결 모습(1)

그림 2.7 UDOO Neo 보드에 HC-SR04 초음파 거리 센서 연결 모습(2)

<HC-SR04 초음파 거리 센서 동작 원리>
그림 2.8 HC-SR04 센서의 동작 원리(1)


그림 2.9 HC-SR04 센서의 동작 원리(2)

a) Trig(Trigger)핀에 10us 정도의 High 신호를 주면 초음파센서는 40khz 펄스를 자동적으로 8번 발생시킨다.
b) 펄스를 발생시킨 직후에 Echo 핀은 High가 되고 반사된 초음파가 감지 되었을 때 Echo 핀은 다시 Low가 된다.
c) 따라서 Echo 핀이 High 상태였다가 Low 상태가 되는데 걸리는 시간(microsecond)을 측정하여서 그 시간을 58(29 * 2, 2는 갔다고 되돌아 오기 때문)로 나누면 거리 값이 나오게 된다.
소리의 속도 계산 공식: 340 meter/second or 29 microseconds/centimeter
(second를 구할 수 있으면 340 을 곱하고, microsecond를 구할 수 있으면 29로 나눠준다)

자, 그렇다면 이제 부터는 HC-SR04 용 device driver를 작성해 보도록 하자.

----------------------------------------------------------------------------------------------------------------------------------------------------------------
/*
 * hc_sr04.c
 * Ultrasonic distance sensor driver for UDOO Neo board.
 *
 * -------------------------------------------------------------------------------------------------
 *    [HC-SR04]                                [UDOO Neo]
 *    VCC(5V)       ..........................  5V
 *    Trig(output) ..........................  GPIO 181
 *    Echo(input)  ..........................  GPIO 180
 *    GND             ..........................  GND
 */

#include <linux/module.h>
#include <linux/init.h>
#include <linux/interrupt.h>
#include <linux/delay.h>
#include <linux/gpio.h>

#define GPIO_HIGH 1
#define GPIO_LOW 0

#define ECHO_VALID 1
#define ECHO_UNVALID 0

#define HC_SR04_ECHO_PIN 180 /* UDOO Neo J4 pin 18 */
#define HC_SR04_TRIG_PIN 181 /* UDOO Neo J4 pin 19 */

static int gpio_irq = -1;
static int echo_valid_flag = 0;
static ktime_t echo_start;
static ktime_t echo_stop;

static ssize_t hc_sr04_value_show(struct class *class, struct class_attribute *attr,
char *buf)  /* /sys/class/hc_sr04/value 파일의 내용을 읽어 들임 - TRIG pin을 설정하여 초음파 소리 전달 시작하도록 만듦. */
{
int counter;

gpio_set_value(HC_SR04_TRIG_PIN, GPIO_HIGH);
udelay(10);   /* datasheet에 의하면 최소 10 us 동안 Trig pin이 HIGH 상태로 유지되어야 함 */
gpio_set_value(HC_SR04_TRIG_PIN, GPIO_LOW);
echo_valid_flag = ECHO_UNVALID;
counter = 0;
while (echo_valid_flag == ECHO_UNVALID) {
if (++counter > 23200) {
return sprintf(buf, "%d\n", -1);
}
udelay(1);
}
return sprintf(buf, "%lld\n", ktime_to_us(ktime_sub(echo_stop, echo_start)));  /* 초음파를 전송한 후, 벽에 부딛혀 돌아오는데 걸린 시간 - microsecond */
}

static ssize_t hc_sr04_value_store(struct class *class, struct class_attribute *attr,
const char *buf, size_t len)  /* /sys/class/hc_sr04/value 파일에 값을 씀 - 실제로는 하는 일 없음 */
{
pr_info(KERN_INFO "Buffer len %d bytes\n", len);
return len;
}

static struct class_attribute hc_sr04_class_attrs[] = {
__ATTR(value, S_IRUGO | S_IWUSR, hc_sr04_value_show, hc_sr04_value_store),
__ATTR_NULL,
};

static struct class hc_sr04_class = {
.name = "hc_sr04",
.owner = THIS_MODULE,
.class_attrs = hc_sr04_class_attrs,
};

static irqreturn_t echo_interrupt_handler(int irq, void *data)   /* echo pin 관련 interrupt handler 함수 - ECHO pin이 HIGH일 때의 시간과 LOW일 때의 시간을 구함, 둘의 차이 값을 거리 계산시 사용함. */
{
ktime_t time_value;

if (echo_valid_flag == ECHO_UNVALID) {
time_value = ktime_get();
if (gpio_get_value(HC_SR04_ECHO_PIN) == GPIO_HIGH) {
echo_start = time_value;
} else {
echo_stop = time_value;
echo_valid_flag = ECHO_VALID;
}
}
return IRQ_HANDLED;
}

static int __init hc_sr04_init(void)
{
int ret;

if (class_register(&hc_sr04_class) < 0) {
pr_info(KERN_ERR "Failed to register a class\n");
goto error;
}

    ret = gpio_request_one(HC_SR04_TRIG_PIN, GPIOF_DIR_OUT, "TRIG");  /* TRIG pin GPIO output 사용 요청 */
    if (ret < 0) {
        pr_info(KERN_ERR "Failed to request gpio for TRIG(%d)\n", ret);
        return -1;
    }

    ret = gpio_request_one(HC_SR04_ECHO_PIN, GPIOF_DIR_IN, "ECHO");  /* ECHO pin GPIO input 사용 요청 */
    if (ret < 0) {
        pr_info(KERN_ERR "Failed to request gpio for ECHO(%d)\n", ret);
        return -1;
    }

ret = gpio_to_irq(HC_SR04_ECHO_PIN);  /* ECHO pin을 interrupt 가능하도록 요청 */
if (ret < 0) {
pr_info(KERN_ERR "Failed to set gpio IRQ(%d)\n", ret);
goto error;
} else {
gpio_irq = ret;
}

ret = request_irq(gpio_irq, echo_interrupt_handler,   /* interrupt handler 등록 */
IRQF_TRIGGER_RISING | IRQF_TRIGGER_FALLING,   /* interrupt 발생 조건 */
"hc-sr04-echo", NULL);
if (ret) {
pr_info(KERN_ERR "Failed to request IRQ(%d)\n", ret);
goto error;
}

return 0;
error:
return -1;
}

static void __exit hc_sr04_exit(void)
{
if (gpio_irq != -1)
        free_irq(gpio_irq, NULL);  /* interrupt 등록 해제 */
gpio_free(HC_SR04_TRIG_PIN);   /* GPIO 설정 해제 */
gpio_free(HC_SR04_ECHO_PIN);  /* GPIO 설정 해제 */

class_unregister(&hc_sr04_class);
}

module_init(hc_sr04_init);
module_exit(hc_sr04_exit);

MODULE_AUTHOR("Tushar Panda");
MODULE_AUTHOR("Chunghan Yi");
MODULE_DESCRIPTION("hc-sr04 ultrasonic distance sensor driver");
MODULE_LICENSE("GPL");
----------------------------------------------------------------------------------------------------------------------------------------------------------------
참고 사항:  위의 코드는 아래 site의 내용을 참조하여 재 작성(개선)하였음을 밝힌다.


----------------------------------------------------------------------------------------------------------------------------------------------------------------
<Makefile>
obj-m +=  hc_sr04.o

export KROOT=/home/chyi/IoT/UDOO/src/buildroot/output/build/linux-4.9

export ARCH=arm

allofit:  modules
modules:
    @$(MAKE) -C $(KROOT) M=$(PWD) modules
modules_install:
    @$(MAKE) -C $(KROOT) M=$(PWD) modules_install
kernel_clean:
    @$(MAKE) -C $(KROOT) M=$(PWD) clean

clean: kernel_clean

    rm -rf   Module.symvers modules.order
----------------------------------------------------------------------------------------------------------------------------------------------------------------
<How to compile>
export KROOT=/home/chyi/IoT/UDOO/src/buildroot/output/build/linux-4.9
export ARCH=arm
export CROSS_COMPILE=arm-linux-
export CC=arm-linux-gcc
export PATH=/home/chyi/IoT/UDOO/src/buildroot/output/host/usr/bin:$PATH
  => cross compile을 위한 환경 변수를 지정한다.

make
  => build하여 kernel module을 생성해 낸다.

sudo cp ./hc_sr04.ko ~/IoT/UDOO/src/buildroot/output/images/rootfs/modules
  => build 결과물을 rootfs(NFS booting 용)의 적당한 위치로 복사한다.

<How to run it on the target board>
  => target board에서 실행한 결과는 다음과 같다.
insmod ./hc_sr04.ko 


그림 2.10 hc-sr04-echo IRQ 등록된 모습

<초음파 거리 센서 동작 확인하기>
# chmod 755 hc_sr04.py
# ./hc_sr04.py
  => 이 파일을 실행하기 위해서는 buildroot에서 Python을 enable시켜 주어야 한다.
  => 책 한권을 센서 앞에 가져다 댄 후, 거리를 측정해 보자.
----------------------------------------------------------------------------------------------------------------------------------------------------------------
#!/usr/bin/python

def distanceCm():
    f = open("/sys/class/hc_sr04/value",'r')
    t = f.read()    #microseconds
    f.close()
    if (long(t) == -1):
        return -1   #N/A
    else:
        return (float(t)/58)  /* device driver에서 microsecond를 되돌려 주므로 29로 나누고, 위에서 구한 시간이 초음파가 나갔다가 되돌아 오는데 걸리는 전체 시간임을 감안하여 다시 2로 나누어 주면 정확한 centimeter 값을 얻을 수 있음 */

def main():
    d = distanceCm()
    print "%.1f cm" % d

if __name__ == "__main__":
    main()
----------------------------------------------------------------------------------------------------------------------------------------------------------------

그림 2.11 hc_sr04.py program을 수행한 결과(나중에 python program 명을 변경함)


3. 적외선 라인 Tracking 센서(FC-03)
이번 절에서 시험할 센서는 Line tracking 센서 FC-03(그림 3.1)이다. 아래 내용은 인터넷에서 발췌한 내용으로 Line tracking 센서의 핵심인 적외선 센서의 동작 원리를 개략적으로 소개해 준다.

"Line tracer나 마이크로 마우스 혹은 다른 마이크로 로봇에서 센서로 사용하는 것 중 가장 많이 사용하는 것이 photo sensor이다. 거리의 측정에도 사용되지만 원거리는 잘 사용하지 않고 근거리를 측정하고자 할 때 사용되기도 하며 물체의 유/무 등 많은 곳에서 사용되고 있다. Photo sensor는 보통 적외선을 많이 이용하고 있는데, 발광부와 수광부로 구성되어 있다. 발광부는 일반 LED와 비슷하지만 가시광선을 내는 것이 아니고 적외선을 발산하게 된다. 반면 수광부는 적외선이 들어온 양에 따라 아날로그 전압이 출력되게 되며, 이 아날로그 신호를 디지털 신호로 바꾸어 MCU에서 사용하면 된다. 수광부는 빛의 양에 따라서 저항값이 변하는 가변저항으로 보아도 될 것이다."
그림 3.1 FC-03 - Uxcell LM393 Chipset Infrared Line Tracking Sensor

<FC-03 라인 Tracking 센서 스펙>
  • Main chip: LM393
  • Designed with reflected infrared sensor, indicator light.
  • Built in a potentiometer for sensitivity control.
  • On-board LM393 voltage comparator chip and infrared sensing probe TCRT5000L
  • Support 5 V / 3.5 V voltage input
  • On-board signal output instructions, output is high effective signal at the same time, the indicator lamp light output signal can be directly and single-chip microcomputer IO connection ·
  • Signal detection sensitivity can adjust
  • Reserve all the way more circuits (P3 voltage drawn)    
  • using TCRT5000 infrared reflection sensor
  • test reflection distance: 1 mm to 25 mm
  • Operation voltage: 3.5v-5V
  • Operation current: >15mA
  • wide voltage LM393 comparator
  • output form: digital switch output (0 and 1)
  • a fixed bolt hole, convenient installation.

FC-03 라인 tracking 센서는 4개의 pin 즉, VCC(3.3V ~ 5V), GND, DO(digital output), AO(analog output)으로 구성되어 있다. 이중 DO와 AO는 둘 중 1개만 사용해도 동작을 확인하는데 문제가 되질 않는다. 따라서 본 실험에서는 DO만 사용할 것이므로, 아래와 같은 pin 연결 구성이 가능할 것이다.

                  [FC-03]                                     [UDOO Neo]
VCC(3.3~5V)   <------------------> 3.3V
D0(digital input)   <------------------>  GPIO 180
A0(analog input)                             NC 
GND                 <----------------->   GND

그림 3.2 UDOO Neo 보드에 FC-03 라인 tracking 센서를 연결한 모습


자, 그렇다면 이제 부터는 FC-03용 device driver를 작성해 보도록 하자. 이미 2절에서 GPIO를 이용한 interrupt 관련 code를 구현해 보았으므로 쉽게 구현이 가능할 것으로 보인다.

----------------------------------------------------------------------------------------------------------------------------------------------------------------
/*
 * fc_03.c
 * Line tracking sensor.
 *
 * ------------------------------------------------------------
 * [FC-03]                                      [UDOO Neo]
 * VCC(3.3~5V)        ......................... 3.3V
 * D0(digital input)  ......................... GPIO 180
 * A0(analog input)   ......................... NC 
 * GND                ......................... GND
 */

#include <linux/module.h>
#include <linux/init.h>
#include <linux/interrupt.h>
#include <linux/delay.h>
#include <linux/gpio.h>

static int fc_03_d0_pin = 180; /* UDOO Neo J4 pin 18 */
static int gpio_irq = 0;

static irqreturn_t line_interrupt_handler(int irq, void *data)   /* interrupt 서비스 루틴 */
{
int value;

value = gpio_get_value(fc_03_d0_pin);   /* fc_03_d0_pin으로 부터 값을 읽어 들임 */
pr_info(KERN_INFO "Value of DO pin is [%d]\n", value);

return IRQ_HANDLED;
}

static int __init fc_03_init(void)
{
int ret;

ret = gpio_request_one(fc_03_d0_pin, GPIOF_DIR_IN, "LINE");   /* fc_03_d0_pin을 gpio input으로 사용할 것을 요청함 */
if (ret < 0) {
pr_info("failed to request GPIO %d, error %d\n", fc_03_d0_pin, ret);
return -1;
}

ret = gpio_to_irq(fc_03_d0_pin);   /* fc_03_d0_pin을 interrupt line을 사용할 것을 요청함 */
if (ret < 0) {
pr_info(KERN_ERR "failed to set gpio IRQ(%d)\n", ret);
goto error;
} else {
gpio_irq = ret;
}

#if 1 /* rising or falling edge 시 interrupt 발생 */
ret = request_irq(gpio_irq, line_interrupt_handler,
IRQF_TRIGGER_RISING | IRQF_TRIGGER_FALLING, "fc-03-line", NULL);
#else /* high 상태일 때 interrupt 발생 */
ret = request_irq(gpio_irq, line_interrupt_handler,
IRQF_TRIGGER_HIGH, "fc-03-line", NULL);
#endif
if (ret) {
pr_info(KERN_ERR "failed to request IRQ(%d)\n", ret);
goto error;
}

return 0;
error:
return -1;
}

static void __exit fc_03_exit(void)
{
synchronize_irq(gpio_irq);
free_irq(gpio_irq, NULL);
gpio_free(fc_03_d0_pin);
}

module_init(fc_03_init);
module_exit(fc_03_exit);

MODULE_AUTHOR("Chunghan Yi");
MODULE_DESCRIPTION("fc-03 line tracking sensor driver");
MODULE_LICENSE("GPL v2");
----------------------------------------------------------------------------------------------------------------------------------------------------------------

<How to run it on the target board>
  => target board에서 실행한 결과는 다음과 같다.
insmod ./fc_03.ko 

그림 3.3 fc_03.ko 모듈 실행 모습 - interrupt 발생 시마다 DO pin 값을 읽어 출력


4. 조도센서(HS-CDSM)
조도센서는 주변의 밝기를 측정하는 센서로써 광에너지(빛)를 받으면 내부에 움직이는 전자가 발생하여 전도율이 변하는 광전효과를 가지는 소자를 사용한다. 특히 황화카드뮴(Cds)를 소자로 사용한 경우, CdS 센서라고 부르는데, CdS 센서는 작고 저렴하기 때문에 가장 보편적으로 사용되고 있다. 예를 들어, 어두워지면 자동으로 켜지는 가로등, 자동차의 헤드라이트, 밝기에 따라 변하는 핸드폰 화면 액정 등이 그 대표적인 예라고 할 수 있다.


그림 4.1 조도 센서(Cds 센서) 개요
그림 4.2 HS-CDSM 조도 센서 외관


그림 4.3 HS-CDSM 조도 센서 내부 구조

HS-CDSM 센서는 3개의 pin 즉, VCC(3.3V ~ 5V), GND, DO(digital output)으로 구성되어 있다. 따라서 아래와 같은 pin 연결 구성이 가능할 것이다.

                  [FC-03]                                     [UDOO Neo]
VCC(3.3~5V)   <------------------> 3.3V
D0(digital input)  <------------------>  GPIO 180
GND                 <----------------->   GND

그림 4.4  UDOO Neo 보드에 HS-CDSM 센서를 연결한 모습

그림 4.5 hs_cdsm.ko를 실행한 모습 - 빛을 차단할 경우 메시지 출력

조도 센서 관련 코드는 3절의 Line Tracking 센서와 크게 차이가 없어 별도로 정리하지 않기로 한다. 필요하다면 아래 github에서 확인해 보기 바란다.



5. 3가지 모션(motion) 센서
이번 절에서는 UDOO Neo 보드에 on board되어 있는 3가지 센서 즉, Accelerometer, MagnetometerGyroscope 관련 device driver를 분석해 보도록 하겠다.

먼저 가속도 센서(accelerometer)는 물체가 점점 빨라지거나 느려지는 것처럼 속도가 변하는 비율(가속도)을 측정하는 장치이고, 자이로 스코프(gyroscope) 센서는 물체가 중심축을 기준으로 회전하는 속도인 각속도(angular velocity)를 측정하는 장치이다. 한편, 다중의 축을 따라서 지구 자기장을 측정할 수 있는 지자기 센서(magnetometer)는 스마트폰의 나침반 및 내비게이션 기능을 구현하거나 드론에서 수평을 유지하는데 주로 사용된다.

아래 그림 5.1은 UDOO Neo 보드의 i2c 연결 관계를 정리해 놓은 것으로, 이 중 I2C_4 controller(master device)에 앞서 언급한 3가지 센서(slave device)가 연결되어 있음을 보여주고 있다.

그림 5.1 UDOO Neo i2c 연결 구성도(I2C_4 controller 주목)

아래 그림 5.2 ~ 5.5의 내용은 FXOS8700CQ Accelerometer & Magnetometer 통합  chip 관련 내용을 정리해 본 것으로 자세한 사항은 관련 datasheet(참고 문헌 [5])를 참고해야 한다.


그림 5.2 NXP FXOS8700CQ accelerometer & magnetometer 통합  chip(1)

그림 5.3 NXP FXOS8700CQ accelerometer & magnetometer 통합  chip(2)

그림 5.4 NXP FXOS8700CQ block diagram

 그림 5.5 NXP FXOS8700CQ pin descriptions

한편, 그림 5.6 ~ 5.9는 FXAS2100X Gyroscope와 관련한 사항으로 자세한 사항은 역시 관련 datasheet(참고 문헌 [6])를 참조해 주기 바란다.


그림 5.6 NXP FXAS2100X gyroscope(1)

그림 5.7 NXP FXAS2100X gyroscope(2)

그림 5.8 NXP FXAS2100X gyroscope block diagram


그림 5.9 NXP FXAS2100X gyroscope pin description

지금까지 기본적인 사항을 살펴 보았으니, 이제부터는 모션 sensor driver를 linux 4.9 kernel에 맞게 porting(굳이 porting이라고 하기도 좀 뭐하지만^^)해 보도록 하자.


<3.14.56 kernel용 motion sensor driver를 4.9 kernel 용으로 porting하기>
cp drivers/input/misc/fxos8700.[ch] ~/buildroot/output/build/linux-4.9/drivers/input/misc
  => accelerometer & magnetometer driver  code를 복사 
cp drivers/input/misc/fxas2100x.c ~/buildroot/output/build/linux-4.9/drivers/input/misc
  => gyroscope code를 복사 

$ cd ~/buildroot/output/build/linux-4.9/drivers/input/misc
$ vi Makefile

$ vi Kconfig

$ cd ~/buildroot/output/build/linux-4.9
$ make linux-menuconfig
Device Drivers --->
      Input device support --->
            Miscellaneous devices
그림 5.10 buildroot kernel에 FXOS8700 및 FXAS2100X code 추가

$ cd arch/arm/boot/dts
  => i2c4 관련 device tree 파일을 수정한다.
그림 5.11 imx6sx-udoo-neo.dtsi 내용 중 accelerometer, gyroscope 관련 device tree 수정

그림 5.12 imx6sx-udoo-neo-full.dts 수정 사항

여기서 잠깐 ! 만일 i2c device(slave)에서 interrupt를 발생시키고자 한다면 ...
----------------------------------------------------------------------------------------------------------------------------------------------------------
만일 accelerometer가 interrupt를 발생시키는 형태로 device driver를 구현하고자 한다면, device tree를 아래와 같이 수정해 주면 된다. 즉, interrupt-parent는 7개의 GPIO controller 중 gpio7로 지정해 주면 된다. 이는 i2c4가 GPIO_202(I2C4_SDA), GPIO_203(I2C4_SCL)를 pinmux해서 사용(그림 2.5 참조)하고 있으므로, gpio7(192 ~ 223)이 적당하다고 볼 수 있다. 그 다음에, interupts = <적당한 숫자, interupt triggering 방식> 형태로 선언해 주면 된다.

&i2c4 {
    pinctrl-names = "default";
    pinctrl-0 = <&pinctrl_i2c4_1>;
    clock-frequency = <100000>;

    accelerometer: fxos8700@1e {
        compatible = "fsl,fxos8700";
        reg = <0x1e>;
        interrupt-parent = <&gpio7>;
        interrupts = <10 IRQ_TYPE_EDGE_BOTH>; /* (7-1) * 32 = 192, 192 + 10 = 202(GPIO_202) */
    };

    gyroscope: fxas2100x@20 {
        compatible = "fsl,fxas2100x";
        reg = <0x20>;
    };
};
그림 5.13 i2c device에서 interrupt 발생 - /proc/interrupts 내용 확인(fxos8700 참조)

참고 사항: 일반적인 device controller는 GIC(interrupt controller)을 자신의 interrupt parent로 설정하지만, i2c device(slave) 같은 consumer device의 경우는 상위 controller(여기서는 gpio controller)를 자신의 interrupt parent로 잡아 주어야 한다.
----------------------------------------------------------------------------------------------------------------------------------------------------------

$ cd ~/buildroot/output/build/linux-4.9
$ make
  => version 차이로 인하여, 위의  수정 사항과 관련하여 error가 발생할 수 있는데, 이를 적절히 수정 !

make linux-rebuild
  => dts(i) file이 build 안될 수 있으니, 재 build하도록 하자.

$ cd ~/buildroot/output/images
$ sudo cp ./zImage /tftpboot/
sudo cp ./imx6sx-udoo-neo-full.dtb /tftpboot/
  => NFS booting을 위해 kernel image와 device tree blob 파일을 /tftpboot로 복사한다.

UDOO Neo 보드를 재부팅 한 후, fxos8700.ko와 fxas2100x.ko module을 구동하도록 하자(편의상 그림 5.10에서 'M'으로 설정하여 kernel module 형태로 build하였음).

<Target board에서 동작 확인하기>
# cd /lib/modules/4.9.0/kernel/drivers/input/misc/
# insmod ./fxos8700.ko
  => accelerometer & magnetometer module을 실행한다.
# insmod ./fxas2100x.ko
 => gyroscope module을 실행한다.
그림 5.14 fxos8700.ko와 fxas2100x.ko kernel module 실행 모습

# cd /sys/devices/virtual/misc/
# cd FreescaleAccelerometer
# echo 1 > enable
  => accelerometer 동작을 enable해 준다.
# cat data 
-200,-816,-16248
...
  => cat data 명령 실행 시 마다 결과 값이 다르게 출력될 것임.
  => Magnetometer 및 Gyroscope도 동일한 방식으로 접근하면 된다.

그림 5.15 3가지 모션 센서 관련 sysfs 내용

여기까지 각각의 device driver가 실제로 동작하는 모습도 살펴 보았으니, 이제 부터는 source code를 분석해 보기로 하자. 코드가 긴 관계로 중요하지 않은 부분은 생략하여 표현하였다.

a) FXOS8700 6-Axis Accelerometer and Magnetometer Combo Sensor

<분석1: fxos8700 driver 제어 방법>
 *-1) /dev/FreescaleAccelerometer, /dev/FreescaleMagnetometer를 open한 후, ioctl( )로 제어하는 방법  *-2) /sys/devices/virtual/misc/FreescaleAccelerometer/sys/devices/virtual/misc/FreescaleMagnetometer 아래의 파일을 제어하는 방법

<분석2: fxos8700 driver data read 방법>
 *-1) /dev/FreescaleAccelerometer, /dev/FreescaleMagnetometer를 open한 후, ioctl( )로 읽어가는 방법
 *-2) /sys/devices/virtual/misc/FreescaleAccelerometer/sys/devices/virtual/misc/FreescaleMagnetometer 아래의 파일을 통해 읽어가능 방법
 *-3) interrupt를 발생 가능하게 하여, input device(예: /dev/input/event1)로 부터 읽어 가능 방법

<분석3: fxos8700 driver 관련하여 사전에 알고 있어야 할 지식>
 *-1) file operations
 *-2) misc device의 동작 방식
 *-3) input device의 동작 방식
 *-4) sysfs 동작 방식
 *-5) i2c device driver 동작 방식

<drivers/input/misc/fxos8700.c>
----------------------------------------------------------------------------------------------------------------------------------------------------------------
/*
 *  fxos8700.c - Linux kernel modules for FXOS8700 6-Axis Acc and Mag 
 *  Combo Sensor 
 *
 *  Copyright (C) 2012-2013 Freescale Semiconductor, Inc. All Rights Reserved.
 *
 *  This program is free software; you can redistribute it and/or modify
 *  it under the terms of the GNU General Public License as published by
 *  the Free Software Foundation; either version 2 of the License, or
 *  (at your option) any later version.
 *
 *  This program is distributed in the hope that it will be useful,
 *  but WITHOUT ANY WARRANTY; without even the implied warranty of
 *  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
 *  GNU General Public License for more details.
 *
 *  You should have received a copy of the GNU General Public License
 *  along with this program; if not, write to the Free Software
 *  Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
 */

#include <linux/module.h>
#include <linux/init.h>
#include <linux/slab.h>
#include <linux/i2c.h>
#include <linux/pm.h>
#include <linux/mutex.h>
#include <linux/delay.h>
#include <linux/interrupt.h>
#include <linux/irq.h>
#include <linux/hwmon-sysfs.h>
#include <linux/err.h>
#include <linux/hwmon.h>
#include <linux/input-polldev.h>
#include <linux/miscdevice.h>
#include <linux/poll.h>
#include "fxos8700.h"

#define FXOS8700_DELAY_DEFAULT 200 /* msecs */
#define FXOS8700_POSITION_DEFAULT 1 /* msecs */

#define FXOS8700_TYPE_ACC 0x00
#define FXOS8700_TYPE_MAG 0x01

#define FXOS8700_STANDBY 0x00
#define FXOS8700_ACTIVED 0x01

#define ABS_STATUS ABS_WHEEL

struct fxos8700_data_axis {  /* accelerometer or magnetometer 센서에서 읽을 들인 data */
short x;
short y;
short z;
};

struct fxos8700_data {   /* accelerometer or magnetometer 센서 관련 data structure */
struct i2c_client *client;   /* i2c client */
struct miscdevice *acc_miscdev;    /* misc device */
struct miscdevice *mag_miscdev;
struct input_dev *acc_idev;   /* input device */
struct input_dev *mag_idev; 
atomic_t acc_delay;
atomic_t mag_delay;
atomic_t acc_active;
atomic_t mag_active;
atomic_t position;
};

static struct fxos8700_data *g_fxos8700_data = NULL;
static int fxos8700_position_settings[8][3][3] = {
{{ 0, -1,  0}, { 1,  0, 0}, {0,  0,  1}},
{{-1,  0,  0}, { 0, -1, 0}, {0,  0,  1}},
{{ 0,  1,  0}, {-1,  0, 0}, {0,  0,  1}},
{{ 1,  0,  0}, { 0,  1, 0}, {0,  0,  1}},

{{ 0, -1,  0}, {-1,  0, 0}, {0,  0, -1}},
{{-1,  0,  0}, { 0,  1, 0}, {0,  0, -1}},
{{ 0,  1,  0}, { 1,  0, 0}, {0,  0, -1}},
{{ 1,  0,  0}, { 0, -1, 0}, {0,  0, -1}},
};

static int fxos8700_data_convert(struct fxos8700_data_axis *axis_data, int position)
{
    ...[생략]...
}

static int fxos8700_change_mode(struct i2c_client *client, int type, int active)
{
    ...[생략]...
}

static int fxos8700_motion_detect_cfg(struct i2c_client *client, u8 threshold, u8 debounce_count)
{
    ...[생략]...
}

static int fxos8700_set_odr(struct i2c_client *client, int type, int delay)
{
    ...[생략]...
}

static int fxos8700_device_init(struct i2c_client *client)  /* fxos8700 초기화 함수. probe() 함수에서 호출함 */
{
int result;
struct fxos8700_data *pdata = i2c_get_clientdata(client);

result = i2c_smbus_write_byte_data(client, FXOS8700_CTRL_REG1, 0x00); //standby mode
if (result < 0)
goto out;
result = i2c_smbus_write_byte_data(client, FXOS8700_M_CTRL_REG1, 0x1F); //
if (result < 0)
goto out;
result = i2c_smbus_write_byte_data(client, FXOS8700_M_CTRL_REG2, 0x5c); //hybrid mode
if (result < 0)
goto out;
result = i2c_smbus_write_byte_data(client, FXOS8700_CTRL_REG1, 0x03 << 3); //odr 50hz
if (result < 0)
goto out;
if (client->irq) {
result = i2c_smbus_write_byte_data(client, FXOS8700_CTRL_REG5, 0xff); //route to pin1
if (result < 0)
goto out;
result = i2c_smbus_write_byte_data(client, FXOS8700_CTRL_REG4, 0x01); //data ready enable
if (result < 0)
goto out;
}
atomic_set(&pdata->acc_active, FXOS8700_STANDBY);
atomic_set(&pdata->mag_active, FXOS8700_STANDBY);
atomic_set(&pdata->position, FXOS8700_POSITION_DEFAULT);
return 0;
out:
dev_err(&client->dev, "error when init fxos8700 device:(%d)", result);
return result;
}

static int fxos8700_device_stop(struct i2c_client *client)
{
i2c_smbus_write_byte_data(client, FXOS8700_CTRL_REG1, 0x00);
return 0;
}

static int fxos8700_read_data(struct i2c_client *client, struct fxos8700_data_axis *data, int type)   /* i2c device로 부터 data를 읽어 들이는 함수 */
{
u8 tmp_data[FXOS8700_DATA_BUF_SIZE];
int ret;
u8 reg;

if (type == FXOS8700_TYPE_ACC)
reg = FXOS8700_OUT_X_MSB;
else
reg = FXOS8700_M_OUT_X_MSB;

ret = i2c_smbus_read_i2c_block_data(client, reg, FXOS8700_DATA_BUF_SIZE, tmp_data);
if (ret < FXOS8700_DATA_BUF_SIZE) {
dev_err(&client->dev, "i2c block read %s failed\n", (type == FXOS8700_TYPE_ACC ? "acc" : "mag"));
return -EIO;
}
data->x = ((tmp_data[0] << 8) & 0xff00) | tmp_data[1];
data->y = ((tmp_data[2] << 8) & 0xff00) | tmp_data[3];
data->z = ((tmp_data[4] << 8) & 0xff00) | tmp_data[5];
return 0;
}

static long fxos8700_acc_ioctl(struct file *file, unsigned int cmd, unsigned long arg)
{
...[생략]...
}

static int fxos8700_acc_open(struct inode *inode, struct file *file)
{
file->private_data = g_fxos8700_data;
return nonseekable_open(inode, file);
}

static int fxos8700_acc_release(struct inode *inode, struct file *file)
{
/* note: releasing the wdt in NOWAYOUT-mode does not stop it */
return 0;
}

static const struct file_operations fxos8700_acc_fops = {  /* /dev/FreescaleAccelerometer에 대한 file operations */
.owner = THIS_MODULE,
.open = fxos8700_acc_open,
.release = fxos8700_acc_release,
.unlocked_ioctl = fxos8700_acc_ioctl,
};

//mag char miscdevice
static long fxos8700_mag_ioctl(struct file *file, unsigned int cmd, unsigned long arg)
{
...[생략]...
}

static int fxos8700_mag_open(struct inode *inode, struct file *file)
{
file->private_data = g_fxos8700_data;
return nonseekable_open(inode, file);
}

static int fxos8700_mag_release(struct inode *inode, struct file *file)
{
/* note: releasing the wdt in NOWAYOUT-mode does not stop it */
return 0;
}

static const struct file_operations fxos8700_mag_fops = {  /* /dev/FreescaleMagnetometer에 대한 file operations */
.owner = THIS_MODULE,
.open = fxos8700_mag_open,
.release = fxos8700_mag_release,
.unlocked_ioctl = fxos8700_mag_ioctl,
};

static struct miscdevice fxos8700_acc_device = {
.minor = MISC_DYNAMIC_MINOR,
.name = "FreescaleAccelerometer",
.fops = &fxos8700_acc_fops,    /* /dev/FreescaleAccelerometer에 대한 file operations 함수 */
};
/* 참고:
struct miscdevice  {
    int minor;
    const char *name;
    const struct file_operations *fops;
    struct list_head list;
    struct device *parent;
    struct device *this_device;
    const struct attribute_group **groups;
    const char *nodename;
    umode_t mode;
};
*/

static struct miscdevice fxos8700_mag_device = {
.minor = MISC_DYNAMIC_MINOR,
.name = "FreescaleMagnetometer",
.fops = &fxos8700_mag_fops,   /* /dev/FreescaleMagnetometer에 대한 file operations 함수 */
};

/*acc and mag share sys interface*/
static ssize_t fxos8700_enable_show(struct device *dev,
struct device_attribute *attr, char *buf)
{
     ...[생략]...
}

static ssize_t fxos8700_enable_store(struct device *dev,
struct device_attribute *attr,
const char *buf, size_t count)
{
     ...[생략]...
}

static ssize_t fxos8700_poll_delay_show(struct device *dev,
struct device_attribute *attr, char *buf)
{
     ...[생략]...
}

static ssize_t fxos8700_poll_delay_store(struct device *dev,
struct device_attribute *attr,
const char *buf, size_t count)
{
     ...[생략]...
}

static ssize_t fxos8700_position_show(struct device *dev,
struct device_attribute *attr, char *buf)
{
     ...[생략]...
}

static ssize_t fxos8700_position_store(struct device *dev,
struct device_attribute *attr,
const char *buf, size_t count)
{
     ...[생략]...
}

static ssize_t fxos8700_data_show(struct device *dev,
struct device_attribute *attr, char *buf)
{
     ...[생략]...
}

static DEVICE_ATTR(enable, S_IRUGO | S_IWUSR,
fxos8700_enable_show, fxos8700_enable_store);
static DEVICE_ATTR(poll_delay, S_IRUGO | S_IWUSR,
fxos8700_poll_delay_show, fxos8700_poll_delay_store);
static DEVICE_ATTR(position, S_IRUGO | S_IWUSR,
fxos8700_position_show, fxos8700_position_store);
static DEVICE_ATTR(data, S_IRUGO | S_IWUSR,
fxos8700_data_show, NULL);
/* 참고: ..................... (A)
struct attribute {
    const char      *name;
    umode_t         mode;
#ifdef CONFIG_DEBUG_LOCK_ALLOC
    bool            ignore_lockdep:1;
    struct lock_class_key   *key;
    struct lock_class_key   skey;
#endif

};
...
struct device_attribute {
    struct attribute    attr;
    ssize_t (*show)(struct device *dev, struct device_attribute *attr,  char *buf); /* sysfs 디렉토리 아래의 파일을 읽을 때 호출되는 함수 */
    ssize_t (*store)(struct device *dev, struct device_attribute *attr, const char *buf, size_t count); /* sysfs 디렉토리 아래의 파일에 값을 쓸 때 호출되는 함수 */

};
...
#define DEVICE_ATTR(_name, _mode, _show, _store) \
    struct device_attribute dev_attr_##_name = __ATTR(_name, _mode, _show, _store)
*/

/*acc only sysfs interface*/
static ssize_t fxos8700_motion_detect_show(struct device *dev,
struct device_attribute *attr, char *buf)
{
     ...[생략]...
}

static ssize_t fxos8700_motion_detect_store(struct device *dev,
struct device_attribute *attr,
const char *buf, size_t count)
{
     ...[생략]...
}

static DEVICE_ATTR(motion_detect, S_IRUGO | S_IWUSR,
fxos8700_motion_detect_show, fxos8700_motion_detect_store);

static struct attribute *fxos8700_acc_attributes[] = {
&dev_attr_enable.attr,       /* (A) 참조 */
&dev_attr_poll_delay.attr,
&dev_attr_position.attr,
&dev_attr_data.attr,
&dev_attr_motion_detect.attr,
NULL
};

static struct attribute *fxos8700_mag_attributes[] = {
&dev_attr_enable.attr,
&dev_attr_poll_delay.attr,
&dev_attr_position.attr,
&dev_attr_data.attr,
NULL
};

static const struct attribute_group fxos8700_acc_attr_group = {
.attrs = fxos8700_acc_attributes,
};

static const struct attribute_group fxos8700_mag_attr_group = {
.attrs = fxos8700_mag_attributes,
};

static int fxos8700_register_sysfs_device(struct fxos8700_data *pdata)   /* sysfs group을 등록해 주는 함수 */
{
struct miscdevice *misc_dev = NULL;
int err = -1;

/*register sysfs for acc*/
misc_dev = pdata->acc_miscdev;
err = sysfs_create_group(&misc_dev->this_device->kobj, &fxos8700_acc_attr_group);  /* sysfs 항목 생성 */
if (err) {
goto out;
}

/*register sysfs for mag*/
misc_dev = pdata->mag_miscdev;
err = sysfs_create_group(&misc_dev->this_device->kobj, &fxos8700_mag_attr_group);   /* sysfs 항목 생성 */
if (err) {
goto err_register_sysfs;
}
return 0;
err_register_sysfs:
misc_dev = pdata->acc_miscdev;
sysfs_remove_group(&misc_dev->this_device->kobj, &fxos8700_acc_attr_group);      /*remove accel senosr sysfs*/
printk("reigster mag sysfs error\n");
out:
printk("reigster acc sysfs error\n");
return err;
}

static int fxos8700_unregister_sysfs_device(struct fxos8700_data *pdata)
{
struct miscdevice *misc_dev = NULL;

misc_dev = pdata->acc_miscdev;
sysfs_remove_group(&misc_dev->this_device->kobj, &fxos8700_acc_attr_group);     /*remove accel senosr sysfs*/

misc_dev = pdata->mag_miscdev;
sysfs_remove_group(&misc_dev->this_device->kobj, &fxos8700_mag_attr_group);     /*remove accel senosr sysfs*/
return 0;
}

/*create acc and mag input device to report sensor raw data, acc motion detect ...*/
static int fxos8700_register_input_device(struct fxos8700_data *pdata)   /* input device로 등록해 주는 함수 */
{
int result;

/*alloc acc input device*/
pdata->acc_idev = input_allocate_device();
if (!pdata->acc_idev) {
result = -ENOMEM;
dev_err(&pdata->client->dev, "alloc FXOS8700 acc input device failed!\n");
goto err_alloc_acc_input_device;
}
pdata->acc_idev->name = "FreescaleAccelerometer";
pdata->acc_idev->id.bustype = BUS_I2C;
pdata->acc_idev->evbit[0] = BIT_MASK(EV_ABS)|BIT_MASK(EV_REL);
input_set_abs_params(pdata->acc_idev, ABS_X, -0x7fff, 0x7fff, 0, 0);
input_set_abs_params(pdata->acc_idev, ABS_Y, -0x7fff, 0x7fff, 0, 0);
input_set_abs_params(pdata->acc_idev, ABS_Z, -0x7fff, 0x7fff, 0, 0);
pdata->acc_idev->relbit[0] = BIT_MASK(REL_X);
result = input_register_device(pdata->acc_idev);
if (result) {
dev_err(&pdata->client->dev, "register FXOS8700 acc input device failed!\n");
goto err_register_acc_input_device;
}

/*alloc mag input device*/
pdata->mag_idev = input_allocate_device();
if (!pdata->mag_idev) {
result = -ENOMEM;
dev_err(&pdata->client->dev, "alloc FXOS8700 mag input device failed!\n");
goto err_alloc_mag_input_device;
}
pdata->mag_idev->name = "FreescaleMagnetometer";
pdata->mag_idev->id.bustype = BUS_I2C;
pdata->mag_idev->evbit[0] = BIT_MASK(EV_ABS);
input_set_abs_params(pdata->mag_idev, ABS_X, -0x7fff, 0x7fff, 0, 0);
input_set_abs_params(pdata->mag_idev, ABS_Y, -0x7fff, 0x7fff, 0, 0);
input_set_abs_params(pdata->mag_idev, ABS_Z, -0x7fff, 0x7fff, 0, 0);
result = input_register_device(pdata->mag_idev);
if (result) {
dev_err(&pdata->client->dev, "register FXOS8700 mag device failed!\n");
goto err_register_mag_input_device;
}
return 0;
err_register_mag_input_device:
input_free_device(pdata->mag_idev);
err_alloc_mag_input_device:
input_unregister_device(pdata->acc_idev);
err_register_acc_input_device:
input_free_device(pdata->acc_idev);
err_alloc_acc_input_device:
return result;
}

static int fxos8700_unregister_input_device(struct fxos8700_data *pdata)
{
if (pdata->acc_idev) {
input_unregister_device(pdata->acc_idev);
input_free_device(pdata->acc_idev);
pdata->acc_idev = NULL;
}
if (pdata->mag_idev) {
input_unregister_device(pdata->mag_idev);
input_free_device(pdata->mag_idev);
pdata->mag_idev = NULL;
}
return 0;
}

static irqreturn_t fxos8700_irq_handler(int irq, void *dev)   /* interrupt handler 함수 - i2c device에서 interrupt를 발생시키도록 설정(device tree)할 경우 사용됨 */
{
int ret;
u8 int_src;
int acc_act, mag_act;
struct fxos8700_data *pdata = (struct fxos8700_data *)dev;
struct fxos8700_data_axis data;

acc_act = atomic_read(&pdata->acc_active);
mag_act = atomic_read(&pdata->mag_active);
int_src = i2c_smbus_read_byte_data(pdata->client, FXOS8700_INT_SOURCE);
if (int_src & 0x01) { //data ready interrupt
ret = fxos8700_read_data(pdata->client, &data, FXOS8700_TYPE_ACC);
if (!ret) {
fxos8700_data_convert(&data, atomic_read(&pdata->position));
if (acc_act) {
input_report_abs(pdata->acc_idev, ABS_X, data.x);
input_report_abs(pdata->acc_idev, ABS_Y, data.y);
input_report_abs(pdata->acc_idev, ABS_Z, data.z);
input_sync(pdata->acc_idev);
}
}
ret = fxos8700_read_data(pdata->client, &data, FXOS8700_TYPE_MAG);
if (!ret) {
fxos8700_data_convert(&data, atomic_read(&pdata->position));
if (mag_act) {
input_report_abs(pdata->mag_idev, ABS_X, data.x);
input_report_abs(pdata->mag_idev, ABS_Y, data.y);
input_report_abs(pdata->mag_idev, ABS_Z, data.z);
input_sync(pdata->mag_idev);
}
}
}
if (int_src & (0x01 << 2)) { //motion detect
i2c_smbus_read_byte_data(pdata->client, FXOS8700_FFMT_SRC); //clear ev flag
input_report_rel(pdata->acc_idev, REL_X, 1);
input_sync(pdata->acc_idev);
}

return IRQ_HANDLED;
}

/* device 초기화시 제일 먼저 호출되는 함수 */
static int fxos8700_probe(struct i2c_client *client, const struct i2c_device_id *id)
{
int result, client_id;
struct fxos8700_data *pdata;
struct i2c_adapter *adapter;

adapter = to_i2c_adapter(client->dev.parent);  /* container_of macro 호출함 */
result = i2c_check_functionality(adapter, I2C_FUNC_SMBUS_BYTE | I2C_FUNC_SMBUS_BYTE_DATA);
if (!result)
goto err_out;

client_id = i2c_smbus_read_byte_data(client, FXOS8700_WHO_AM_I);   /* client_id 값을 구함 - i2c bus를 통해 읽어 들임 */
  if (client_id != FXOS8700_DEVICE_ID && client_id != FXOS8700_PRE_DEVICE_ID) {
dev_err(&client->dev,
"read chip ID 0x%x is not equal to 0x%x or 0x%x\n",
result, FXOS8700_DEVICE_ID,FXOS8700_PRE_DEVICE_ID);
result = -EINVAL;
goto err_out;
  }
pdata = kzalloc(sizeof(struct fxos8700_data), GFP_KERNEL);   /* struct fxos8700_data를 위한 메모리 할당 */
if (!pdata) {
result = -ENOMEM;
dev_err(&client->dev, "alloc data memory error!\n");
goto err_out;
}
g_fxos8700_data = pdata;
pdata->client = client;
atomic_set(&pdata->acc_delay, FXOS8700_DELAY_DEFAULT);
atomic_set(&pdata->mag_delay, FXOS8700_DELAY_DEFAULT);
i2c_set_clientdata(client, pdata);   /* driver_data 설정 */

result = misc_register(&fxos8700_acc_device);   /* accelerometer를 misc device로 등록 */
if (result != 0) {
printk(KERN_ERR "register acc miscdevice error");
goto err_regsiter_acc_misc;
}
pdata->acc_miscdev = &fxos8700_acc_device;

result = misc_register(&fxos8700_mag_device);  /* magnetometer를 misc device로 등록 */
if (result != 0) {
printk(KERN_ERR "register acc miscdevice error");
goto err_regsiter_mag_misc;
}
pdata->mag_miscdev = &fxos8700_mag_device;

result = fxos8700_register_sysfs_device(pdata);   /* accelerometer & magnetometer에 대한 sysfs 등록 */
if (result) {
dev_err(&client->dev, "create device file failed!\n");
result = -EINVAL;
goto err_register_sys;
}
result = fxos8700_register_input_device(pdata);  /* accelerometer & magnetometer를 input device로 등록 */
if (result) {
dev_err(&client->dev, "create device file failed!\n");
result = -EINVAL;
goto err_register_input_device;
}
if (client->irq) {   /* i2c slave device에서 interrupt 발생하도록 device tree에서 설정한 경우, threaded interrupt handler 요청 */
result= request_threaded_irq(client->irq, NULL, fxos8700_irq_handler,
IRQF_TRIGGER_LOW | IRQF_ONESHOT, client->dev.driver->name, pdata);
if (result < 0) {
dev_err(&client->dev, "failed to register fxos8700 irq %d!\n", client->irq);
goto err_register_irq;
}
}
fxos8700_device_init(client);  /* fxos8700 device 초기화 - i2c write 함수 호출 */
printk("%s succ\n", __FUNCTION__);
  return 0;
err_register_irq:
fxos8700_unregister_input_device(pdata);
err_register_input_device:
fxos8700_unregister_sysfs_device(pdata);
err_register_sys:
misc_deregister(&fxos8700_mag_device);
pdata->mag_miscdev = NULL;
err_regsiter_mag_misc:
misc_deregister(&fxos8700_acc_device);
pdata->acc_miscdev = NULL;
err_regsiter_acc_misc:
i2c_set_clientdata(client,NULL);
kfree(pdata);
err_out:
return result;
}

static int fxos8700_remove(struct i2c_client *client)
{
struct fxos8700_data *pdata = i2c_get_clientdata(client);

if (!pdata)
return 0;
fxos8700_device_stop(client);
fxos8700_unregister_sysfs_device(pdata);
misc_deregister(&fxos8700_acc_device);
misc_deregister(&fxos8700_mag_device);
kfree(pdata);
return 0;
}

#ifdef CONFIG_PM_SLEEP
static int fxos8700_suspend(struct device *dev)   /* power managenet -  suspend 함수 */
{
struct i2c_client *client = to_i2c_client(dev);
struct fxos8700_data *pdata = i2c_get_clientdata(client);

if (atomic_read(&pdata->acc_active)|| atomic_read(&pdata->mag_active))
fxos8700_device_stop(client);
return 0;
}

static int fxos8700_resume(struct device *dev)  /* power managenet -  resume 함수 */
{
int ret = 0;
struct i2c_client *client = to_i2c_client(dev);
struct fxos8700_data *pdata = i2c_get_clientdata(client);

if (atomic_read(&pdata->acc_active))
fxos8700_change_mode(client, FXOS8700_TYPE_ACC, FXOS8700_ACTIVED);
if (atomic_read(&pdata->mag_active))
fxos8700_change_mode(client, FXOS8700_TYPE_MAG, FXOS8700_ACTIVED);
return ret;
}
#endif

static struct of_device_id fs_fxos8700_match[] = {
{
.compatible = "fsl,fxos8700",   /* device tree의 compatible string과 matching되는 부분 */
},
{},
};
MODULE_DEVICE_TABLE(of, fs_fxos8700_match);
/* 참고 :
#define MODULE_DEVICE_TABLE(type, name)                 \
extern const typeof(name) __mod_##type##__##name##_device_table     \
  __attribute__ ((unused, alias(__stringify(name))))
*/

static const struct i2c_device_id fxos8700_id[] = {
{"fxos8700", 0},
{ }
};
MODULE_DEVICE_TABLE(i2c, fxos8700_id);

static SIMPLE_DEV_PM_OPS(fxos8700_pm_ops, fxos8700_suspend, fxos8700_resume);
static struct i2c_driver fxos8700_driver = {
.driver = {   /* device driver 등록 시 사용되는 structure */
.name = "fxos8700",
.owner = THIS_MODULE,
.of_match_table = fs_fxos8700_match,
.pm = &fxos8700_pm_ops,
},
.probe = fxos8700_probe,   /* driver 초기화 시 제일 먼저 호출되는 함수 */
.remove = fxos8700_remove,
.id_table = fxos8700_id,
};

static int __init fxos8700_init(void)
{
/* register driver */
int res;

res = i2c_add_driver(&fxos8700_driver);  /* i2c_register_driver() call - 아래 코드 5.3 참조 -> driver로 등록한 후, i2c adapter 에 연결하는 일을 수행함 */
if (res < 0) {
printk(KERN_INFO "add fxos8700 i2c driver failed\n");
return -ENODEV;
}
return res;
}

static void __exit fxos8700_exit(void)
{
i2c_del_driver(&fxos8700_driver);
}

MODULE_AUTHOR("Freescale Semiconductor, Inc.");
MODULE_DESCRIPTION("FXOS8700 6-Axis Acc and Mag Combo Sensor driver");
MODULE_LICENSE("GPL");

module_init(fxos8700_init);
module_exit(fxos8700_exit);
----------------------------------------------------------------------------------------------------------------------------------------------------------------
아래 코드 5.1 ~ 5.3은 i2c device driver를 등록하는 과정에서 필요한 주요 data structure와 함수를 정리해 본 것이다.

코드 5.1 struct device_driver

코드 5.2 struct i2c_driver

코드 5.3 i2c_register_driver 함수


b) 3-Axis Gyroscope sensor
fxas2100x 드라이버는 코드 구성에 있어 fxos7800 드라이버와 크게 차이가 없다. 따라서 여기서는 상세한 코드 설명은 생략하기로 하겠다.

<drivers/input/misc/fxas2100x.c>
----------------------------------------------------------------------------------------------------------------------------------------------------------------
/*
 *  fxas2100x.c - Linux kernel modules for 3-Axis Gyroscope sensor
 *  Copyright (C) 2014-2015 Freescale Semiconductor, Inc. All Rights Reserved.
 *
 *  This program is free software; you can redistribute it and/or modify
 *  it under the terms of the GNU General Public License as published by
 *  the Free Software Foundation; either version 2 of the License, or
 *  (at your option) any later version.
 *
 *  This program is distributed in the hope that it will be useful,
 *  but WITHOUT ANY WARRANTY; without even the implied warranty of
 *  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
 *  GNU General Public License for more details.
 *
 *  You should have received a copy of the GNU General Public License
 *  along with this program; if not, write to the Free Software
 *  Foundation, Inc., 675 Mass Ave, Cambridge, MA 02139, USA.
 */

#include <linux/module.h>
#include <linux/init.h>
#include <linux/slab.h>
#include <linux/i2c.h>
#include <linux/pm.h>
#include <linux/mutex.h>
#include <linux/delay.h>
#include <linux/interrupt.h>
#include <linux/irq.h>
#include <linux/hwmon-sysfs.h>
#include <linux/err.h>
#include <linux/hwmon.h>
#include <linux/input-polldev.h>
#include <linux/miscdevice.h>
#include <linux/poll.h>

#define SENSOR_IOCTL_BASE 'S'
#define SENSOR_GET_MODEL_NAME _IOR(SENSOR_IOCTL_BASE, 0, char *)
#define SENSOR_GET_POWER_STATUS _IOR(SENSOR_IOCTL_BASE, 2, int)
#define SENSOR_SET_POWER_STATUS _IOR(SENSOR_IOCTL_BASE, 3, int)
#define SENSOR_GET_DELAY_TIME _IOR(SENSOR_IOCTL_BASE, 4, int)
#define SENSOR_SET_DELAY_TIME _IOR(SENSOR_IOCTL_BASE, 5, int)
#define SENSOR_GET_RAW_DATA _IOR(SENSOR_IOCTL_BASE, 6, short[3])

#define FXAS2100X_I2C_ADDR         0x20

#define FXAS21000_CHIP_ID   0xD1

#define FXAS21002_CHID_ID_1   0xD6
#define FXAS21002_CHID_ID_2   0xD7

#define FXAS2100X_POSITION_DEFAULT 2
#define FXAS2100X_DELAY_DEFAULT 200

#define FXAS2100X_STATUS_ZYXDR    0x08
#define FXAS2100X_BUF_SIZE    6

/* register enum for fxas2100x registers */
enum {
FXAS2100X_STATUS = 0x00,
FXAS2100X_OUT_X_MSB,
FXAS2100X_OUT_X_LSB,
FXAS2100X_OUT_Y_MSB,
FXAS2100X_OUT_Y_LSB,
FXAS2100X_OUT_Z_MSB,
FXAS2100X_OUT_Z_LSB,
FXAS2100X_DR_STATUS,
FXAS2100X_F_STATUS,
FXAS2100X_F_SETUP,
FXAS2100X_F_EVENT,
FXAS2100X_INT_SRC_FLAG,
FXAS2100X_WHO_AM_I,
FXAS2100X_CTRL_REG0,
FXAS2100X_RT_CFG,
FXAS2100X_RT_SRC,
FXAS2100X_RT_THS,
FXAS2100X_RT_COUNT,
FXAS2100X_TEMP,
FXAS2100X_CTRL_REG1,
FXAS2100X_CTRL_REG2,
FXAS2100X_CTRL_REG3, // fxos21002 special
FXAS2100X_REG_END,
};

enum {
STANDBY = 0,
ACTIVED,
};

struct fxas2100x_data_axis {
short x;
short y;
short z;
};

struct fxas2100x_data {
struct i2c_client *client;
struct input_dev *idev;
atomic_t active;
atomic_t delay;
atomic_t position;
u8 chip_id;
};

static struct fxas2100x_data *g_fxas2100x_data = NULL;

static int fxas2100x_position_setting[8][3][3] = {
{ {  0, -1,  0 }, {  1, 0,  0 }, {  0,  0,  1 } },
{ { -1,  0,  0 }, {  0, -1,  0 }, {  0,  0,  1 } },
{ {  0, 1,  0 }, { -1,  0,  0 }, {  0,  0,  1 } },
{ {  1, 0,  0 }, {  0, 1,  0 }, {  0,  0,  1 } },

{ {  0, -1,  0 }, { -1,  0,  0 }, {  0,  0, -1 } },
{ { -1,  0,  0 }, {  0, 1,  0 }, {  0,  0, -1 } },
{ {  0, 1,  0 }, {  1, 0,  0 }, {  0,  0, -1 } },
{ {  1, 0,  0 }, {  0, -1,  0 }, {  0,  0, -1 } },
};

static int fxas2100x_data_convert(struct fxas2100x_data *pdata,
struct fxas2100x_data_axis *axis_data)
{
   ... [생략] ...
}

static int fxas2100x_device_init(struct i2c_client *client)
{
int result;
u8 val;
struct fxas2100x_data *pdata = i2c_get_clientdata(client);

if(pdata->chip_id == FXAS21000_CHIP_ID)
val = (0x01 << 2);            /*fxas21000 dr 200HZ */
else
val = (0x02 << 2);  /*fxas21002 dr 200HZ */
result = i2c_smbus_write_byte_data(client, FXAS2100X_CTRL_REG1,val);
if (result < 0)
goto out;
if (client->irq) {
val = 0x01 << 3;  // if  route to pin2 val = 0x00 << 3 , if pin1 , val = 0x01 << 3
val |= 0x01 << 2; //data ready interrupt enabale
result = i2c_smbus_write_byte_data(client, FXAS2100X_CTRL_REG2,val);
if (result < 0)
goto out;
}
atomic_set(&pdata->active,STANDBY);
return 0;
out:
dev_err(&client->dev, "error when init fxas2100x:(%d)", result);
return result;
}

static int fxas2100x_change_mode(struct i2c_client *client, int mode)
{
   ...[생략]....
}

static int fxas2100x_set_delay(struct i2c_client *client, int delay)
{
   ...[생략]...
}

static int fxas2100x_device_stop(struct i2c_client *client)
{
   ...[생략]...
}

static int fxas2100x_read_data(struct fxas2100x_data *pdata,
struct fxas2100x_data_axis *data)
{
    struct i2c_client *client = pdata->client;
int x, y, z;
u8 tmp_data[FXAS2100X_BUF_SIZE];
int ret;

ret = i2c_smbus_read_i2c_block_data(client,
   FXAS2100X_OUT_X_MSB,
FXAS2100X_BUF_SIZE, tmp_data);
if (ret < FXAS2100X_BUF_SIZE) {
dev_err(&client->dev, "i2c block read failed\n");
return -EIO;
}
data->x = ((tmp_data[0] << 8) & 0xff00) | tmp_data[1];
data->y = ((tmp_data[2] << 8) & 0xff00) | tmp_data[3];
data->z = ((tmp_data[4] << 8) & 0xff00) | tmp_data[5];
if (pdata->chip_id ==  FXAS21000_CHIP_ID) {
x = data->x;
y = data->y;
z = data->z;
x = x * 4 / 5;
y = y * 4 / 5;
z = z * 4 / 5;
data->x = x;
data->y = y;
data->z = z;
}
return 0;
}

//fxas2100x miscdevice
static long fxas2100x_ioctl(struct file *file, unsigned int cmd, unsigned long arg)
{
... [생략]...
}

static int fxas2100x_open(struct inode *inode, struct file *file)
{
   ...[생략]...
}

static int fxas2100x_release(struct inode *inode, struct file *file)
{
   ...[생략]...
}

static const struct file_operations fxas2100x_fops = {
.owner = THIS_MODULE,
.open = fxas2100x_open,
.release = fxas2100x_release,
.unlocked_ioctl = fxas2100x_ioctl,
};

static struct miscdevice fxas2100x_device = {
.minor = MISC_DYNAMIC_MINOR,
.name = "FreescaleGyroscope",
.fops = &fxas2100x_fops,
};

static ssize_t fxas2100x_enable_show(struct device *dev,
  struct device_attribute *attr, char *buf)
{
   ...[생략]...
}

static ssize_t fxas2100x_enable_store(struct device *dev,
   struct device_attribute *attr,
   const char *buf, size_t count)
{
  ...[생략]...
}

static ssize_t fxas2100x_poll_delay_show(struct device *dev,
  struct device_attribute *attr, char *buf)
{
   ...[생략]...
}

static ssize_t fxas2100x_poll_delay_store(struct device *dev,
   struct device_attribute *attr,
   const char *buf, size_t count)
{
   ...[생략]...
}

static ssize_t fxas2100x_position_show(struct device *dev,
    struct device_attribute *attr, char *buf)
{
  ...[생략]...
}

static ssize_t fxas2100x_position_store(struct device *dev,
     struct device_attribute *attr,
     const char *buf, size_t count)
{
  ...[생략]...
}

static ssize_t fxas2100x_data_show(struct device *dev,
    struct device_attribute *attr, char *buf)
{
   ...[생략]...
}

static DEVICE_ATTR(enable, S_IRUGO | S_IWUSR,
fxas2100x_enable_show, fxas2100x_enable_store);
static DEVICE_ATTR(poll_delay, S_IRUGO | S_IWUSR,
fxas2100x_poll_delay_show, fxas2100x_poll_delay_store);
static DEVICE_ATTR(position, S_IRUGO | S_IWUSR,
fxas2100x_position_show, fxas2100x_position_store);
static DEVICE_ATTR(data, S_IRUGO | S_IWUSR,
fxas2100x_data_show, NULL);

static struct attribute *fxas2100x_attributes[] = {
&dev_attr_enable.attr,
&dev_attr_poll_delay.attr,
&dev_attr_position.attr,
&dev_attr_data.attr,
NULL
};

static const struct attribute_group fxas2100x_attr_group = {
.attrs = fxas2100x_attributes,
};

static irqreturn_t fxas2100x_irq_handler(int irq, void *dev)
{
int ret,enable;
u8 int_src;
struct fxas2100x_data *pdata = (struct fxas2100x_data *)dev;
struct fxas2100x_data_axis data;

enable = atomic_read(&pdata->active);
int_src = i2c_smbus_read_byte_data(pdata->client, FXAS2100X_INT_SRC_FLAG);
if (int_src & 0x01) {
ret = fxas2100x_read_data(pdata, &data);
if (!ret) {
fxas2100x_data_convert(pdata, &data);
if (enable) {
input_report_abs(pdata->idev, ABS_X, data.x);
input_report_abs(pdata->idev, ABS_Y, data.y);
input_report_abs(pdata->idev, ABS_Z, data.z);
input_sync(pdata->idev);
}
}
}
return IRQ_HANDLED;
}

static int fxas2100x_probe(struct i2c_client *client,
  const struct i2c_device_id *id)
{
int result, chip_id;
struct fxas2100x_data *pdata;
struct i2c_adapter *adapter;

adapter = to_i2c_adapter(client->dev.parent);
result = i2c_check_functionality(adapter, I2C_FUNC_SMBUS_BYTE | I2C_FUNC_SMBUS_BYTE_DATA);
if (!result)
goto err_out;

chip_id = i2c_smbus_read_byte_data(client, FXAS2100X_WHO_AM_I);

if (chip_id != FXAS21000_CHIP_ID && chip_id != FXAS21002_CHID_ID_1 && chip_id != FXAS21002_CHID_ID_2) {
dev_err(&client->dev,"read chip ID 0x%x is not equal to 0x%x for fxos21000) or 0x%x/0x%x,(fxos21002) !\n",
chip_id, FXAS21000_CHIP_ID, FXAS21002_CHID_ID_1, FXAS21002_CHID_ID_2);
result = -EINVAL;
goto err_out;
}
pdata = kzalloc(sizeof(struct fxas2100x_data), GFP_KERNEL);
if (!pdata) {
result = -ENOMEM;
dev_err(&client->dev, "alloc data memory error!\n");
goto err_out;
}
/* Initialize the FXAS2100X chip */
g_fxas2100x_data = pdata;
pdata->client = client;
pdata->chip_id = chip_id;
atomic_set(&pdata->delay, FXAS2100X_DELAY_DEFAULT);
atomic_set(&pdata->position, FXAS2100X_POSITION_DEFAULT);
i2c_set_clientdata(client, pdata);
result = misc_register(&fxas2100x_device);
if (result != 0) {
printk(KERN_ERR "register acc miscdevice error");
goto err_regsiter_misc;
}

result = sysfs_create_group(&fxas2100x_device.this_device->kobj, &fxas2100x_attr_group);
if (result) {
dev_err(&client->dev, "create device file failed!\n");
result = -EINVAL;
goto err_create_sysfs;
}

/*create data  input device*/
pdata->idev = input_allocate_device();
if (!pdata->idev) {
result = -ENOMEM;
dev_err(&client->dev, "alloc fxas2100x input device failed!\n");
goto err_alloc_input_device;
}
pdata->idev->name = "FreescaleGyroscope";
pdata->idev->id.bustype = BUS_I2C;
pdata->idev->evbit[0] = BIT_MASK(EV_ABS);
input_set_abs_params(pdata->idev, ABS_X, -0x7fff, 0x7fff, 0, 0);
input_set_abs_params(pdata->idev, ABS_Y, -0x7fff, 0x7fff, 0, 0);
input_set_abs_params(pdata->idev, ABS_Z, -0x7fff, 0x7fff, 0, 0);
result = input_register_device(pdata->idev);
if (result) {
dev_err(&client->dev, "register fxas2100x input device failed!\n");
goto err_register_input_device;
}

if (client->irq) {
result= request_threaded_irq(client->irq, NULL, fxas2100x_irq_handler,
 IRQF_TRIGGER_LOW | IRQF_ONESHOT, client->dev.driver->name, pdata);
if (result < 0) {
dev_err(&client->dev, "failed to register MMA8x5x irq %d!\n",
client->irq);
goto err_register_irq;
}
}
fxas2100x_device_init(client);
printk(KERN_INFO "fxas2100x device driver probe successfully\n");
return 0;
err_register_irq:
input_unregister_device(pdata->idev);
err_register_input_device:
input_free_device(pdata->idev);
err_alloc_input_device:
sysfs_remove_group(&fxas2100x_device.this_device->kobj, &fxas2100x_attr_group);
err_create_sysfs:
misc_deregister(&fxas2100x_device);
err_regsiter_misc:
kfree(pdata);
err_out:
return result;
}

static int fxas2100x_remove(struct i2c_client *client)
{
struct fxas2100x_data *pdata = i2c_get_clientdata(client);

fxas2100x_device_stop(client);
misc_deregister(&fxas2100x_device);
if (pdata != NULL)
kfree(pdata);
return 0;
}

#ifdef CONFIG_PM_SLEEP
static int fxas2100x_suspend(struct device *dev)
{
struct i2c_client *client = to_i2c_client(dev);
struct fxas2100x_data *pdata = i2c_get_clientdata(client);

if (atomic_read(&pdata->active))
fxas2100x_device_stop(client);
return 0;
}

static int fxas2100x_resume(struct device *dev)
{
int val = 0;
struct i2c_client *client = to_i2c_client(dev);
struct fxas2100x_data *pdata = i2c_get_clientdata(client);

if (atomic_read(&pdata->active)) {
val = i2c_smbus_read_byte_data(client, FXAS2100X_CTRL_REG1);
val &= ~0x03;
val |= 0x02;
i2c_smbus_write_byte_data(client, FXAS2100X_CTRL_REG1, val);
}
return 0;

}
#endif

static struct of_device_id fs_fxas2100x_match[] = {
{
.compatible = "fsl,fxas2100x",
},
{},
};
MODULE_DEVICE_TABLE(of, fs_fxas2100x_match);

static const struct i2c_device_id fxas2100x_id[] = {
{ "fxas2100x", 0 },
{ }
};
MODULE_DEVICE_TABLE(i2c, fxas2100x_id);

static SIMPLE_DEV_PM_OPS(fxas2100x_pm_ops, fxas2100x_suspend, fxas2100x_resume);
static struct i2c_driver fxas2100x_driver = {
.class = I2C_CLASS_HWMON,
.driver = {
.name = "fxas2100x",
.owner = THIS_MODULE,
.of_match_table = fs_fxas2100x_match,
.pm = &fxas2100x_pm_ops,
},
.probe = fxas2100x_probe,
.remove = fxas2100x_remove,
.id_table = fxas2100x_id,
};

static int __init fxas2100x_init(void)
{
/* register driver */
int res;

res = i2c_add_driver(&fxas2100x_driver);
if (res < 0) {
printk(KERN_INFO "add fxas2100x i2c driver failed\n");
return -ENODEV;
}
return res;
}

static void __exit fxas2100x_exit(void)
{
i2c_del_driver(&fxas2100x_driver);
}

MODULE_AUTHOR("Freescale Semiconductor, Inc.");
MODULE_DESCRIPTION("FXAS2100X 3-Axis Gyrosope Sensor driver");
MODULE_LICENSE("GPL");

module_init(fxas2100x_init);
module_exit(fxas2100x_exit);
----------------------------------------------------------------------------------------------------------------------------------------------------------------

이상으로 몇가지 센서 관련 device driver를 구현하고 그 코드를 분석해 보았다. 부족한 부분은 다음 시간에 좀 더 보강해 볼 것을 약속하며 이번 posting을 마치고자 한다.


References
1. Make: Sensors, Projects and Experiments to Measure the World with Arduino and Raspberry Pi, Tero Karvinen, Kimmo Karvinen & Ville Valtokari, Maker Media
2. Make: Getting started with sensors, Tero Karvinen, Kimmo Karvinen, Maker Media
3. Make: Arduino Bots and Gadgets, Tero Karvinen, Kimmo Karvinen, Maker Media
4. HC-SR04.pdf 등 internet 여러 site ...
5. FXOS8700CQ.pdf, 6-axis sensor with integrated linear accelerometer and magnetometer, NXP
6. FXAS21002.pdf, 3-Axis Digital Angular Rate Gyroscope, NXP

Slowboot


댓글 없음:

댓글 쓰기