x_pigpiod_if.c
Go to the documentation of this file.
00001 /*
00002 gcc -Wall -pthread -o x_pigpiod_if x_pigpiod_if.c -lpigpiod_if
00003 ./x_pigpiod_if
00004 
00005 *** WARNING ************************************************
00006 *                                                          *
00007 * All the tests make extensive use of gpio 25 (pin 22).    *
00008 * Ensure that either nothing or just a LED is connected to *
00009 * gpio 25 before running any of the tests.                 *
00010 *                                                          *
00011 * Some tests are statistical in nature and so may on       *
00012 * occasion fail.  Repeated failures on the same test or    *
00013 * many failures in a group of tests indicate a problem.    *
00014 ************************************************************
00015 */
00016 
00017 #include <stdio.h>
00018 #include <sys/types.h>
00019 #include <sys/stat.h>
00020 #include <fcntl.h>
00021 #include <unistd.h>
00022 #include <string.h>
00023 #include <ctype.h>
00024 
00025 #include "pigpiod_if.h"
00026 
00027 #define GPIO 25
00028 
00029 void CHECK(int t, int st, int got, int expect, int pc, char *desc)
00030 {
00031    if ((got >= (((1E2-pc)*expect)/1E2)) && (got <= (((1E2+pc)*expect)/1E2)))
00032    {
00033       printf("TEST %2d.%-2d PASS (%s: %d)\n", t, st, desc, expect);
00034    }
00035    else
00036    {
00037       fprintf(stderr,
00038               "TEST %2d.%-2d FAILED got %d (%s: %d)\n",
00039               t, st, got, desc, expect);
00040    }
00041 }
00042 
00043 void t0()
00044 {
00045    printf("\nTesting pigpiod C I/F 1\n");
00046 
00047    printf("pigpio version %d.\n", get_pigpio_version());
00048 
00049    printf("Hardware revision %d.\n", get_hardware_revision());
00050 }
00051 
00052 void t1()
00053 {
00054    int v;
00055 
00056    printf("Mode/PUD/read/write tests.\n");
00057 
00058    set_mode(GPIO, PI_INPUT);
00059    v = get_mode(GPIO);
00060    CHECK(1, 1, v, 0, 0, "set mode, get mode");
00061 
00062    set_pull_up_down(GPIO, PI_PUD_UP);
00063    v = gpio_read(GPIO);
00064    CHECK(1, 2, v, 1, 0, "set pull up down, read");
00065 
00066    set_pull_up_down(GPIO, PI_PUD_DOWN);
00067    v = gpio_read(GPIO);
00068    CHECK(1, 3, v, 0, 0, "set pull up down, read");
00069 
00070    gpio_write(GPIO, PI_LOW);
00071    v = get_mode(GPIO);
00072    CHECK(1, 4, v, 1, 0, "write, get mode");
00073 
00074    v = gpio_read(GPIO);
00075    CHECK(1, 5, v, 0, 0, "read");
00076 
00077    gpio_write(GPIO, PI_HIGH);
00078    v = gpio_read(GPIO);
00079    CHECK(1, 6, v, 1, 0, "write, read");
00080 }
00081 
00082 int t2_count=0;
00083 
00084 void t2cb(unsigned gpio, unsigned level, uint32_t tick)
00085 {
00086    t2_count++;
00087 }
00088 
00089 void t2()
00090 {
00091    int dc, f, r, rr, oc;
00092 
00093    printf("PWM dutycycle/range/frequency tests.\n");
00094 
00095    set_PWM_range(GPIO, 255);
00096    set_PWM_frequency(GPIO, 0);
00097    f = get_PWM_frequency(GPIO);
00098    CHECK(2, 1, f, 10, 0, "set PWM range, set/get PWM frequency");
00099 
00100    callback(GPIO, EITHER_EDGE, t2cb);
00101 
00102    set_PWM_dutycycle(GPIO, 0);
00103    dc = get_PWM_dutycycle(GPIO);
00104    CHECK(2, 2, dc, 0, 0, "get PWM dutycycle");
00105 
00106    time_sleep(0.5); /* allow old notifications to flush */
00107    oc = t2_count;
00108    time_sleep(2);
00109    f = t2_count - oc;
00110    CHECK(2, 3, f, 0, 0, "set PWM dutycycle, callback");
00111 
00112    set_PWM_dutycycle(GPIO, 128);
00113    dc = get_PWM_dutycycle(GPIO);
00114    CHECK(2, 4, dc, 128, 0, "get PWM dutycycle");
00115 
00116    time_sleep(0.2);
00117    oc = t2_count;
00118    time_sleep(2);
00119    f = t2_count - oc;
00120    CHECK(2, 5, f, 40, 5, "set PWM dutycycle, callback");
00121 
00122    set_PWM_frequency(GPIO, 100);
00123    f = get_PWM_frequency(GPIO);
00124    CHECK(2, 6, f, 100, 0, "set/get PWM frequency");
00125 
00126    time_sleep(0.2);
00127    oc = t2_count;
00128    time_sleep(2);
00129    f = t2_count - oc;
00130    CHECK(2, 7, f, 400, 1, "callback");
00131 
00132    set_PWM_frequency(GPIO, 1000);
00133    f = get_PWM_frequency(GPIO);
00134    CHECK(2, 8, f, 1000, 0, "set/get PWM frequency");
00135 
00136    time_sleep(0.2);
00137    oc = t2_count;
00138    time_sleep(2);
00139    f = t2_count - oc;
00140    CHECK(2, 9, f, 4000, 1, "callback");
00141 
00142    r = get_PWM_range(GPIO);
00143    CHECK(2, 10, r, 255, 0, "get PWM range");
00144 
00145    rr = get_PWM_real_range(GPIO);
00146    CHECK(2, 11, rr, 200, 0, "get PWM real range");
00147 
00148    set_PWM_range(GPIO, 2000);
00149    r = get_PWM_range(GPIO);
00150    CHECK(2, 12, r, 2000, 0, "set/get PWM range");
00151 
00152    rr = get_PWM_real_range(GPIO);
00153    CHECK(2, 13, rr, 200, 0, "get PWM real range");
00154 
00155    set_PWM_dutycycle(GPIO, 0);
00156 }
00157 
00158 int t3_reset=1;
00159 int t3_count=0;
00160 uint32_t t3_tick=0;
00161 float t3_on=0.0;
00162 float t3_off=0.0;
00163 
00164 void t3cbf(unsigned gpio, unsigned level, uint32_t tick)
00165 {
00166    uint32_t td;
00167 
00168    if (t3_reset)
00169    {
00170       t3_count = 0;
00171       t3_on = 0.0;
00172       t3_off = 0.0;
00173       t3_reset = 0;
00174    }
00175    else
00176    {
00177       td = tick - t3_tick;
00178 
00179       if (level == 0) t3_on += td;
00180       else            t3_off += td;
00181    }
00182 
00183    t3_count ++;
00184    t3_tick = tick;
00185 }
00186 
00187 void t3()
00188 {
00189    int pw[3]={500, 1500, 2500};
00190    int dc[4]={20, 40, 60, 80};
00191 
00192    int f, rr, v;
00193    float on, off;
00194 
00195    int t;
00196 
00197    printf("PWM/Servo pulse accuracy tests.\n");
00198 
00199    callback(GPIO, EITHER_EDGE, t3cbf);
00200 
00201    for (t=0; t<3; t++)
00202    {
00203       set_servo_pulsewidth(GPIO, pw[t]);
00204       v = get_servo_pulsewidth(GPIO);
00205       CHECK(3, t+t+1, v, pw[t], 0, "get servo pulsewidth");
00206 
00207       time_sleep(1);
00208       t3_reset = 1;
00209       time_sleep(4);
00210       on = t3_on;
00211       off = t3_off;
00212       CHECK(3, t+t+2, (1000.0*(on+off))/on, 20000000.0/pw[t], 1,
00213          "set servo pulsewidth");
00214    }
00215 
00216    set_servo_pulsewidth(GPIO, 0);
00217    set_PWM_frequency(GPIO, 1000);
00218    f = get_PWM_frequency(GPIO);
00219    CHECK(3, 7, f, 1000, 0, "set/get PWM frequency");
00220 
00221    rr = set_PWM_range(GPIO, 100);
00222    CHECK(3, 8, rr, 200, 0, "set PWM range");
00223 
00224    for (t=0; t<4; t++)
00225    {
00226       set_PWM_dutycycle(GPIO, dc[t]);
00227       v = get_PWM_dutycycle(GPIO);
00228       CHECK(3, t+t+9, v, dc[t], 0, "get PWM dutycycle");
00229 
00230       time_sleep(1);
00231       t3_reset = 1;
00232       time_sleep(2);
00233       on = t3_on;
00234       off = t3_off;
00235       CHECK(3, t+t+10, (1000.0*on)/(on+off), 10.0*dc[t], 1,
00236          "set PWM dutycycle");
00237    }
00238 
00239    set_PWM_dutycycle(GPIO, 0);
00240 
00241 }
00242 
00243 void t4()
00244 {
00245    int h, e, f, n, s, b, l, seq_ok, toggle_ok;
00246    gpioReport_t r;
00247    char p[32];
00248 
00249    printf("Pipe notification tests.\n");
00250 
00251    set_PWM_frequency(GPIO, 0);
00252    set_PWM_dutycycle(GPIO, 0);
00253    set_PWM_range(GPIO, 100);
00254 
00255    h = notify_open();
00256 
00257    sprintf(p, "/dev/pigpio%d", h);
00258    f = open(p, O_RDONLY);
00259 
00260    e = notify_begin(h, (1<<GPIO));
00261    CHECK(4, 1, e, 0, 0, "notify open/begin");
00262 
00263    set_PWM_dutycycle(GPIO, 50);
00264    time_sleep(4);
00265    set_PWM_dutycycle(GPIO, 0);
00266 
00267    e = notify_pause(h);
00268    CHECK(4, 2, e, 0, 0, "notify pause");
00269 
00270    e = notify_close(h);
00271    CHECK(4, 3, e, 0, 0, "notify close");
00272 
00273    n = 0;
00274    s = 0;
00275    l = 0;
00276    seq_ok = 1;
00277    toggle_ok = 1;
00278 
00279    while (1)
00280    {
00281       b = read(f, &r, 12);
00282       if (b == 12)
00283       {
00284          if (s != r.seqno) seq_ok = 0;
00285 
00286          if (n) if (l != (r.level&(1<<GPIO))) toggle_ok = 0;
00287 
00288          if (r.level&(1<<GPIO)) l = 0;
00289          else                   l = (1<<GPIO);
00290            
00291          s++;
00292          n++;
00293 
00294          // printf("%d %d %d %X\n", r.seqno, r.flags, r.tick, r.level);
00295       }
00296       else break;
00297    }
00298    close(f);
00299  
00300    CHECK(4, 4, seq_ok, 1, 0, "sequence numbers ok");
00301 
00302    CHECK(4, 5, toggle_ok, 1, 0, "gpio toggled ok");
00303 
00304    CHECK(4, 6, n, 80, 10, "number of notifications");
00305 }
00306 
00307 int t5_count = 0;
00308 
00309 void t5cbf(unsigned gpio, unsigned level, uint32_t tick)
00310 {
00311    t5_count++;
00312 }
00313 
00314 void t5()
00315 {
00316    int BAUD=4800;
00317 
00318    char *TEXT=
00319 "\n\
00320 Now is the winter of our discontent\n\
00321 Made glorious summer by this sun of York;\n\
00322 And all the clouds that lour'd upon our house\n\
00323 In the deep bosom of the ocean buried.\n\
00324 Now are our brows bound with victorious wreaths;\n\
00325 Our bruised arms hung up for monuments;\n\
00326 Our stern alarums changed to merry meetings,\n\
00327 Our dreadful marches to delightful measures.\n\
00328 Grim-visaged war hath smooth'd his wrinkled front;\n\
00329 And now, instead of mounting barded steeds\n\
00330 To fright the souls of fearful adversaries,\n\
00331 He capers nimbly in a lady's chamber\n\
00332 To the lascivious pleasing of a lute.\n\
00333 ";
00334 
00335    gpioPulse_t wf[] =
00336    {
00337       {1<<GPIO, 0,  10000},
00338       {0, 1<<GPIO,  30000},
00339       {1<<GPIO, 0,  60000},
00340       {0, 1<<GPIO, 100000},
00341    };
00342 
00343    int e, oc, c, wid;
00344 
00345    char text[2048];
00346 
00347    printf("Waveforms & serial read/write tests.\n");
00348 
00349    callback(GPIO, FALLING_EDGE, t5cbf);
00350 
00351    set_mode(GPIO, PI_OUTPUT);
00352 
00353    e = wave_clear();
00354    CHECK(5, 1, e, 0, 0, "callback, set mode, wave clear");
00355 
00356    e = wave_add_generic(4, wf);
00357    CHECK(5, 2, e, 4, 0, "pulse, wave add generic");
00358 
00359    wid = wave_create();
00360    e = wave_send_repeat(wid);
00361    if (e < 14) CHECK(5, 3, e,  9, 0, "wave tx repeat");
00362    else        CHECK(5, 3, e, 19, 0, "wave tx repeat");
00363 
00364    oc = t5_count;
00365    time_sleep(5.05);
00366    c = t5_count - oc;
00367    CHECK(5, 4, c, 50, 2, "callback");
00368 
00369    e = wave_tx_stop();
00370    CHECK(5, 5, e, 0, 0, "wave tx stop");
00371 
00372    e = bb_serial_read_open(GPIO, BAUD, 8);
00373    CHECK(5, 6, e, 0, 0, "serial read open");
00374 
00375    wave_clear();
00376    e = wave_add_serial(GPIO, BAUD, 8, 2, 5000000, strlen(TEXT), TEXT);
00377    CHECK(5, 7, e, 3405, 0, "wave clear, wave add serial");
00378 
00379    wid = wave_create();
00380    e = wave_send_once(wid);
00381    if (e < 6964) CHECK(5, 8, e, 6811, 0, "wave tx start");
00382    else          CHECK(5, 8, e, 7116, 0, "wave tx start");
00383 
00384    oc = t5_count;
00385    time_sleep(3);
00386    c = t5_count - oc;
00387    CHECK(5, 9, c, 0, 0, "callback");
00388 
00389    oc = t5_count;
00390    while (wave_tx_busy()) time_sleep(0.1);
00391    time_sleep(0.1);
00392    c = t5_count - oc;
00393    CHECK(5, 10, c, 1702, 0, "wave tx busy, callback");
00394 
00395    c = bb_serial_read(GPIO, text, sizeof(text)-1);
00396    if (c > 0) text[c] = 0; /* null terminate string */
00397    CHECK(5, 11, strcmp(TEXT, text), 0, 0, "wave tx busy, serial read");
00398 
00399    e = bb_serial_read_close(GPIO);
00400    CHECK(5, 12, e, 0, 0, "serial read close");
00401 
00402    c = wave_get_micros();
00403    CHECK(5, 13, c, 6158148, 0, "wave get micros");
00404 
00405    c = wave_get_high_micros();
00406    if (c > 6158148) c = 6158148;
00407    CHECK(5, 14, c, 6158148, 0, "wave get high micros");
00408 
00409    c = wave_get_max_micros();
00410    CHECK(5, 15, c, 1800000000, 0, "wave get max micros");
00411 
00412    c = wave_get_pulses();
00413    CHECK(5, 16, c, 3405, 0, "wave get pulses");
00414 
00415    c = wave_get_high_pulses();
00416    CHECK(5, 17, c, 3405, 0, "wave get high pulses");
00417 
00418    c = wave_get_max_pulses();
00419    CHECK(5, 18, c, 12000, 0, "wave get max pulses");
00420 
00421    c = wave_get_cbs();
00422    if (c < 6963) CHECK(5, 19, c, 6810, 0, "wave get cbs");
00423    else          CHECK(5, 19, c, 7115, 0, "wave get cbs");
00424 
00425    c = wave_get_high_cbs();
00426    if (c < 6963) CHECK(5, 20, c, 6810, 0, "wave get high cbs");
00427    else          CHECK(5, 20, c, 7115, 0, "wave get high cbs");
00428 
00429    c = wave_get_max_cbs();
00430    CHECK(5, 21, c, 25016, 0, "wave get max cbs");
00431 }
00432 
00433 int t6_count=0;
00434 int t6_on=0;
00435 uint32_t t6_on_tick=0;
00436 
00437 void t6cbf(unsigned gpio, unsigned level, uint32_t tick)
00438 {
00439    if (level == 1)
00440    {
00441       t6_on_tick = tick;
00442       t6_count++;
00443    }
00444    else
00445    {
00446       if (t6_on_tick) t6_on += (tick - t6_on_tick);
00447    }
00448 }
00449 
00450 void t6()
00451 {
00452    int tp, t, p;
00453 
00454    printf("Trigger tests.\n");
00455 
00456    gpio_write(GPIO, PI_LOW);
00457 
00458    tp = 0;
00459 
00460    callback(GPIO, EITHER_EDGE, t6cbf);
00461 
00462    time_sleep(0.2);
00463 
00464    for (t=0; t<5; t++)
00465    {
00466       time_sleep(0.1);
00467       p = 10 + (t*10);
00468       tp += p;
00469       gpio_trigger(GPIO, p, 1);
00470    }
00471 
00472    time_sleep(0.5);
00473 
00474    CHECK(6, 1, t6_count, 5, 0, "gpio trigger count");
00475 
00476    CHECK(6, 2, t6_on, tp, 25, "gpio trigger pulse length");
00477 }
00478 
00479 int t7_count=0;
00480 
00481 void t7cbf(unsigned gpio, unsigned level, uint32_t tick)
00482 {
00483    if (level == PI_TIMEOUT) t7_count++;
00484 }
00485 
00486 void t7()
00487 {
00488    int c, oc;
00489 
00490    printf("Watchdog tests.\n");
00491 
00492    /* type of edge shouldn't matter for watchdogs */
00493    callback(GPIO, FALLING_EDGE, t7cbf);
00494 
00495    set_watchdog(GPIO, 50); /* 50 ms, 20 per second */
00496    time_sleep(0.5);
00497    oc = t7_count;
00498    time_sleep(2);
00499    c = t7_count - oc;
00500    CHECK(7, 1, c, 39, 5, "set watchdog on count");
00501 
00502    set_watchdog(GPIO, 0); /* 0 switches watchdog off */
00503    time_sleep(0.5);
00504    oc = t7_count;
00505    time_sleep(2);
00506    c = t7_count - oc;
00507    CHECK(7, 2, c, 0, 1, "set watchdog off count");
00508 }
00509 
00510 void t8()
00511 {
00512    int v;
00513 
00514    printf("Bank read/write tests.\n");
00515 
00516    gpio_write(GPIO, 0);
00517    v = read_bank_1() & (1<<GPIO);
00518    CHECK(8, 1, v, 0, 0, "read bank 1");
00519 
00520    gpio_write(GPIO, 1);
00521    v = read_bank_1() & (1<<GPIO);
00522    CHECK(8, 2, v, (1<<GPIO), 0, "read bank 1");
00523 
00524    clear_bank_1(1<<GPIO);
00525    v = gpio_read(GPIO);
00526    CHECK(8, 3, v, 0, 0, "clear bank 1");
00527 
00528    set_bank_1(1<<GPIO);
00529    v = gpio_read(GPIO);
00530    CHECK(8, 4, v, 1, 0, "set bank 1");
00531 
00532    v = read_bank_2();
00533 
00534    if (v) v = 0; else v = 1;
00535 
00536    CHECK(8, 5, v, 0, 0, "read bank 2");
00537 
00538    v = clear_bank_2(0);
00539    CHECK(8, 6, v, 0, 0, "clear bank 2");
00540 
00541    v = clear_bank_2(0xffffff);
00542    CHECK(8, 7, v, PI_SOME_PERMITTED, 0, "clear bank 2");
00543 
00544    v = set_bank_2(0);
00545    CHECK(8, 8, v, 0, 0, "set bank 2");
00546 
00547    v = set_bank_2(0xffffff);
00548    CHECK(8, 9, v, PI_SOME_PERMITTED, 0, "set bank 2");
00549 }
00550 
00551 int t9_count = 0;
00552 
00553 void t9cbf(unsigned gpio, unsigned level, uint32_t tick)
00554 {
00555    t9_count++;
00556 }
00557 
00558 void t9()
00559 {
00560    int s, oc, c, e;
00561    uint32_t p[10];
00562 
00563    printf("Script store/run/status/stop/delete tests.\n");
00564 
00565    gpio_write(GPIO, 0); /* need known state */
00566 
00567    /*
00568    100 loops per second
00569    p0 number of loops
00570    p1 GPIO
00571    */
00572    char *script="\
00573    ld p9 p0\
00574    tag 0\
00575    w p1 1\
00576    mils 5\
00577    w p1 0\
00578    mils 5\
00579    dcr p9\
00580    jp 0";
00581 
00582    callback(GPIO, RISING_EDGE, t9cbf);
00583 
00584    s = store_script(script);
00585 
00586    /* Wait for script to finish initing. */
00587    while (1)
00588    {
00589       time_sleep(0.1);
00590       e = script_status(s, p);
00591       if (e != PI_SCRIPT_INITING) break;
00592    }
00593 
00594    oc = t9_count;
00595    p[0] = 99;
00596    p[1] = GPIO;
00597    run_script(s, 2, p);
00598    time_sleep(2);
00599    c = t9_count - oc;
00600    CHECK(9, 1, c, 100, 0, "store/run script");
00601 
00602    oc = t9_count;
00603    p[0] = 200;
00604    p[1] = GPIO;
00605    run_script(s, 2, p);
00606    while (1)
00607    {
00608       time_sleep(0.1);
00609       e = script_status(s, p);
00610       if (e != PI_SCRIPT_RUNNING) break;
00611    }
00612    c = t9_count - oc;
00613    time_sleep(0.1);
00614    CHECK(9, 2, c, 201, 0, "run script/script status");
00615 
00616    oc = t9_count;
00617    p[0] = 2000;
00618    p[1] = GPIO;
00619    run_script(s, 2, p);
00620    while (1)
00621    {
00622       time_sleep(0.1);
00623       e = script_status(s, p);
00624       if (e != PI_SCRIPT_RUNNING) break;
00625       if (p[9] < 1600) stop_script(s);
00626    }
00627    c = t9_count - oc;
00628    time_sleep(0.1);
00629    CHECK(9, 3, c, 410, 10, "run/stop script/script status");
00630 
00631    e = delete_script(s);
00632    CHECK(9, 4, e, 0, 0, "delete script");
00633 }
00634 
00635 void ta()
00636 {
00637    int h, b, e;
00638    char *TEXT;
00639    char text[2048];
00640 
00641    printf("Serial link tests.\n");
00642 
00643    /* this test needs RXD and TXD to be connected */
00644 
00645    h = serial_open("/dev/ttyAMA0", 57600, 0);
00646 
00647    CHECK(10, 1, h, 0, 0, "serial open");
00648 
00649    time_sleep(0.1); /* allow time for transmission */
00650 
00651    b = serial_read(h, text, sizeof(text)); /* flush buffer */
00652 
00653    b = serial_data_available(h);
00654    CHECK(10, 2, b, 0, 0, "serial data available");
00655 
00656    TEXT = "\
00657 To be, or not to be, that is the question-\
00658 Whether 'tis Nobler in the mind to suffer\
00659 The Slings and Arrows of outrageous Fortune,\
00660 Or to take Arms against a Sea of troubles,\
00661 ";
00662    e = serial_write(h, TEXT, strlen(TEXT));
00663    CHECK(10, 3, e, 0, 0, "serial write");
00664 
00665    e = serial_write_byte(h, 0xAA);
00666    e = serial_write_byte(h, 0x55);
00667    e = serial_write_byte(h, 0x00);
00668    e = serial_write_byte(h, 0xFF);
00669 
00670    CHECK(10, 4, e, 0, 0, "serial write byte");
00671 
00672    time_sleep(0.1); /* allow time for transmission */
00673 
00674    b = serial_data_available(h);
00675    CHECK(10, 5, b, strlen(TEXT)+4, 0, "serial data available");
00676 
00677    b = serial_read(h, text, strlen(TEXT));
00678    CHECK(10, 6, b, strlen(TEXT), 0, "serial read");
00679    if (b >= 0) text[b] = 0;
00680    CHECK(10, 7, strcmp(TEXT, text), 0, 0, "serial read");
00681 
00682    b = serial_read_byte(h);
00683    CHECK(10, 8, b, 0xAA, 0, "serial read byte");
00684 
00685    b = serial_read_byte(h);
00686    CHECK(10, 9, b, 0x55, 0, "serial read byte");
00687 
00688    b = serial_read_byte(h);
00689    CHECK(10, 10, b, 0x00, 0, "serial read byte");
00690 
00691    b = serial_read_byte(h);
00692    CHECK(10, 11, b, 0xFF, 0, "serial read byte");
00693 
00694    b = serial_data_available(h);
00695    CHECK(10, 12, b, 0, 0, "serial data availabe");
00696 
00697    e = serial_close(h);
00698    CHECK(10, 13, e, 0, 0, "serial close");
00699 }
00700 
00701 void tb()
00702 {
00703    int h, e, b, len;
00704    char *exp;
00705    char buf[128];
00706 
00707    printf("SMBus / I2C tests.");
00708 
00709    /* this test requires an ADXL345 on I2C bus 1 addr 0x53 */
00710 
00711    h = i2c_open(1, 0x53, 0);
00712    CHECK(11, 1, h, 0, 0, "i2c open");
00713 
00714    e = i2c_write_device(h, "\x00", 1); /* move to known register */
00715    CHECK(11, 2, e, 0, 0, "i2c write device");
00716 
00717    b = i2c_read_device(h, buf, 1);
00718    CHECK(11, 3, b, 1, 0, "i2c read device");
00719    CHECK(11, 4, buf[0], 0xE5, 0, "i2c read device");
00720 
00721    b = i2c_read_byte(h);
00722    CHECK(11, 5, b, 0xE5, 0, "i2c read byte");
00723 
00724    b = i2c_read_byte_data(h, 0);
00725    CHECK(11, 6, b, 0xE5, 0, "i2c read byte data");
00726 
00727    b = i2c_read_byte_data(h, 48);
00728    CHECK(11, 7, b, 2, 0, "i2c read byte data");
00729 
00730    exp = "\x1D[aBcDeFgHjKM]";
00731    len = strlen(exp);
00732 
00733    e = i2c_write_device(h, exp, len);
00734    CHECK(11, 8, e, 0, 0, "i2c write device");
00735 
00736    e = i2c_write_device(h, "\x1D", 1);
00737    b = i2c_read_device(h, buf, len-1);
00738    CHECK(11, 9, b, len-1, 0, "i2c read device");
00739    CHECK(11, 10, strncmp(buf, exp+1, len-1), 0, 0, "i2c read device");
00740 
00741    if (strncmp(buf, exp+1, len-1))
00742       printf("got [%.*s] expected [%.*s]\n", len-1, buf, len-1, exp+1);
00743 
00744    e = i2c_write_byte_data(h, 0x1d, 0xAA);
00745    CHECK(11, 11, e, 0, 0, "i2c write byte data");
00746 
00747    b = i2c_read_byte_data(h, 0x1d);
00748    CHECK(11, 12, b, 0xAA, 0, "i2c read byte data");
00749 
00750    e = i2c_write_byte_data(h, 0x1d, 0x55);
00751    CHECK(11, 13, e, 0, 0, "i2c write byte data");
00752 
00753    b = i2c_read_byte_data(h, 0x1d);
00754    CHECK(11, 14, b, 0x55, 0, "i2c read byte data");
00755 
00756    exp = "[1234567890#]";
00757    len = strlen(exp);
00758 
00759    e = i2c_write_block_data(h, 0x1C, exp, len);
00760    CHECK(11, 15, e, 0, 0, "i2c write block data");
00761 
00762    e = i2c_write_device(h, "\x1D", 1);
00763    b = i2c_read_device(h, buf, len);
00764    CHECK(11, 16, b, len, 0, "i2c read device");
00765    CHECK(11, 17, strncmp(buf, exp, len), 0, 0, "i2c read device");
00766 
00767    if (strncmp(buf, exp, len))
00768       printf("got [%.*s] expected [%.*s]\n", len, buf, len, exp);
00769 
00770    b = i2c_read_i2c_block_data(h, 0x1D, buf, len);
00771    CHECK(11, 18, b, len, 0, "i2c read i2c block data");
00772    CHECK(11, 19, strncmp(buf, exp, len), 0, 0, "i2c read i2c block data");
00773 
00774    if (strncmp(buf, exp, len))
00775       printf("got [%.*s] expected [%.*s]\n", len, buf, len, exp);
00776 
00777    exp = "(-+=;:,<>!%)";
00778    len = strlen(exp);
00779 
00780    e = i2c_write_i2c_block_data(h, 0x1D, exp, len);
00781    CHECK(11, 20, e, 0, 0, "i2c write i2c block data");
00782 
00783    b = i2c_read_i2c_block_data(h, 0x1D, buf, len);
00784    CHECK(11, 21, b, len, 0, "i2c read i2c block data");
00785    CHECK(11, 22, strncmp(buf, exp, len), 0, 0, "i2c read i2c block data");
00786 
00787    if (strncmp(buf, exp, len))
00788       printf("got [%.*s] expected [%.*s]\n", len, buf, len, exp);
00789 
00790    e = i2c_close(h);
00791    CHECK(11, 23, e, 0, 0, "i2c close");
00792 }
00793 
00794 void tc()
00795 {
00796    int h, x, b, e;
00797    char buf[128];
00798 
00799    printf("SPI tests.");
00800 
00801    /* this test requires a MCP3202 on SPI channel 1 */
00802 
00803    h = spi_open(1, 50000, 0);
00804    CHECK(12, 1, h, 0, 0, "spi open");
00805 
00806 
00807    for (x=0; x<5; x++)
00808    {
00809       sprintf(buf, "\x01\x80");
00810       b = spi_xfer(h, buf, buf, 3);
00811       CHECK(12, 2, b, 3, 0, "spi xfer");
00812       if (b == 3)
00813       {
00814          time_sleep(1.0);
00815          printf("%d ", ((buf[1]&0x0F)*256)|buf[2]);
00816       }
00817    }
00818 
00819    e = spi_close(h);
00820    CHECK(12, 99, e, 0, 0, "spi close");
00821 }
00822 
00823 
00824 int main(int argc, char *argv[])
00825 {
00826    int i, t, c, status;
00827 
00828    char test[64]={0,};
00829 
00830    if (argc > 1)
00831    {
00832       t = 0;
00833 
00834       for (i=0; i<strlen(argv[1]); i++)
00835       {
00836          c = tolower(argv[1][i]);
00837 
00838          if (!strchr(test, c))
00839          {
00840             test[t++] = c;
00841             test[t] = 0;
00842          }
00843       }
00844    }
00845    else strcat(test, "0123456789");
00846 
00847    status = pigpio_start(0, 0);
00848 
00849    if (status < 0)
00850    {
00851       fprintf(stderr, "pigpio initialisation failed.\n");
00852       return 1;
00853    }
00854 
00855    printf("Connected to pigpio daemon.\n");
00856 
00857    if (strchr(test, '0')) t0();
00858    if (strchr(test, '1')) t1();
00859    if (strchr(test, '2')) t2();
00860    if (strchr(test, '3')) t3();
00861    if (strchr(test, '4')) t4();
00862    if (strchr(test, '5')) t5();
00863    if (strchr(test, '6')) t6();
00864    if (strchr(test, '7')) t7();
00865    if (strchr(test, '8')) t8();
00866    if (strchr(test, '9')) t9();
00867    if (strchr(test, 'a')) ta();
00868    if (strchr(test, 'b')) tb();
00869    if (strchr(test, 'c')) tc();
00870 
00871    pigpio_stop();
00872 
00873    return 0;
00874 }
00875 


cob_hand_bridge
Author(s): Mathias Lüdtke
autogenerated on Thu Jun 6 2019 20:43:57