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


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