diff --git a/command.c b/command.c index 683b587..a2bc7c4 100644 --- a/command.c +++ b/command.c @@ -26,7 +26,7 @@ For more information, please refer to */ /* -This version is for pigpio version 14+ +This version is for pigpio version 16+ */ #include @@ -42,72 +42,133 @@ cmdInfo_t cmdInfo[]= { /* num str vfyt retv */ - {PI_CMD_BC1, "BC1", 111, 1}, - {PI_CMD_BC2, "BC2", 111, 1}, - {PI_CMD_BR1, "BR1", 101, 3}, - {PI_CMD_BR2, "BR2", 101, 3}, - {PI_CMD_BS1, "BS1", 111, 1}, - {PI_CMD_BS2, "BS2", 111, 1}, - {PI_CMD_HELP, "H", 101, 5}, - {PI_CMD_HELP, "HELP", 101, 5}, - {PI_CMD_HWVER, "HWVER", 101, 4}, - {PI_CMD_MICS, "MICS", 112, 0}, - {PI_CMD_MILS, "MILS", 112, 0}, - {PI_CMD_MODEG, "MG" , 112, 2}, - {PI_CMD_MODEG, "MODEG", 112, 2}, - {PI_CMD_MODES, "M", 125, 0}, - {PI_CMD_MODES, "MODES", 125, 0}, - {PI_CMD_NB, "NB", 122, 0}, - {PI_CMD_NC, "NC", 112, 0}, - {PI_CMD_NO, "NO", 101, 2}, - {PI_CMD_NP, "NP", 112, 0}, - {PI_CMD_PARSE, "PARSE", 115, 2}, - {PI_CMD_PFG, "PFG", 112, 2}, - {PI_CMD_PFS, "PFS", 121, 2}, - {PI_CMD_PIGPV, "PIGPV", 101, 4}, - {PI_CMD_PRG, "PRG", 112, 2}, - {PI_CMD_PROC, "PROC", 115, 2}, - {PI_CMD_PROCD, "PROCD", 112, 2}, - {PI_CMD_PROCP, "PROCP", 112, 7}, - {PI_CMD_PROCR, "PROCR", 191, 2}, - {PI_CMD_PROCS, "PROCS", 112, 2}, - {PI_CMD_PRRG, "PRRG", 112, 2}, - {PI_CMD_PRS, "PRS", 121, 2}, - {PI_CMD_PUD, "PUD", 126, 0}, - {PI_CMD_PWM, "P", 121, 0}, - {PI_CMD_PWM, "PWM", 121, 0}, - {PI_CMD_READ, "R", 112, 2}, - {PI_CMD_READ, "READ", 112, 2}, - {PI_CMD_SERVO, "S", 121, 0}, - {PI_CMD_SERVO, "SERVO", 121, 0}, - {PI_CMD_SLR, "SLR", 121, 6}, - {PI_CMD_SLRC, "SLRC", 112, 2}, - {PI_CMD_SLRO, "SLRO", 121, 2}, - {PI_CMD_TICK, "T", 101, 4}, - {PI_CMD_TICK, "TICK", 101, 4}, - {PI_CMD_TRIG, "TRIG", 131, 0}, - {PI_CMD_WDOG, "WDOG", 121, 0}, - {PI_CMD_WRITE, "W", 121, 0}, - {PI_CMD_WRITE, "WRITE", 121, 0}, - {PI_CMD_WVAG, "WVAG", 192, 2}, - {PI_CMD_WVAS, "WVAS", 141, 2}, - {PI_CMD_WVBSY, "WVBSY", 101, 2}, - {PI_CMD_WVCLR, "WVCLR", 101, 2}, - {PI_CMD_WVCRE, "WVCRE", 101, 2}, - {PI_CMD_WVDEL, "WVDEL", 112, 2}, - {PI_CMD_WVGO, "WVGO" , 101, 2}, - {PI_CMD_WVGOR, "WVGOR", 101, 2}, - {PI_CMD_WVHLT, "WVHLT", 101, 2}, - {PI_CMD_WVNEW, "WVNEW", 101, 2}, - {PI_CMD_WVSC, "WVSC", 112, 2}, - {PI_CMD_WVSM, "WVSM", 112, 2}, - {PI_CMD_WVSP, "WVSP", 112, 2}, - {PI_CMD_WVTX, "WVTX", 112, 2}, - {PI_CMD_WVTXR, "WVTXR", 112, 2}, + {PI_CMD_BC1, "BC1", 111, 1}, // gpioWrite_Bits_0_31_Clear + {PI_CMD_BC2, "BC2", 111, 1}, // gpioWrite_Bits_32_53_Clear + + {PI_CMD_BR1, "BR1", 101, 3}, // gpioRead_Bits_0_31 + {PI_CMD_BR2, "BR2", 101, 3}, // gpioRead_Bits_32_53 + + {PI_CMD_BS1, "BS1", 111, 1}, // gpioWrite_Bits_0_31_Set + {PI_CMD_BS2, "BS2", 111, 1}, // gpioWrite_Bits_32_53_Set + + {PI_CMD_HELP, "H", 101, 5}, // cmdUsage + {PI_CMD_HELP, "HELP", 101, 5}, // cmdUsage + + {PI_CMD_HWVER, "HWVER", 101, 4}, // gpioHardwareRevision + + {PI_CMD_I2CC, "I2CC", 112, 0}, // i2cClose + {PI_CMD_I2CO, "I2CO", 131, 2}, // i2cOpen + + {PI_CMD_I2CPC, "I2CPC", 131, 2}, // i2cProcessCall + {PI_CMD_I2CPK, "I2CPK", 194, 6}, // i2cBlockProcessCall + + {PI_CMD_I2CRB, "I2CRB", 121, 2}, // i2cReadByteData + {PI_CMD_I2CRD, "I2CRD", 121, 6}, // i2cReadDevice + {PI_CMD_I2CRI, "I2CRI", 131, 6}, // i2cReadI2CBlockData + {PI_CMD_I2CRK, "I2CRK", 121, 6}, // i2cReadBlockData + {PI_CMD_I2CRS, "I2CRS", 112, 2}, // i2cReadByte + {PI_CMD_I2CRW, "I2CRW", 121, 2}, // i2cReadWordData + + {PI_CMD_I2CWB, "I2CWB", 131, 0}, // i2cWriteByteData + {PI_CMD_I2CWD, "I2CWD", 193, 0}, // i2cWriteDevice + {PI_CMD_I2CWI, "I2CWI", 194, 0}, // i2cWriteI2CBlockData + {PI_CMD_I2CWK, "I2CWK", 194, 0}, // i2cWriteBlockData + {PI_CMD_I2CWQ, "I2CWQ", 121, 0}, // i2cWriteQuick + {PI_CMD_I2CWS, "I2CWS", 121, 0}, // i2cWriteByte + {PI_CMD_I2CWW, "I2CWW", 131, 0}, // i2cWriteWordData + + {PI_CMD_MICS, "MICS", 112, 0}, // gpioDelay + {PI_CMD_MILS, "MILS", 112, 0}, // gpioDelay + + {PI_CMD_MODEG, "MG" , 112, 2}, // gpioGetMode + {PI_CMD_MODEG, "MODEG", 112, 2}, // gpioGetMode + + {PI_CMD_MODES, "M", 125, 0}, // gpioSetMode + {PI_CMD_MODES, "MODES", 125, 0}, // gpioSetMode + + {PI_CMD_NB, "NB", 122, 0}, // gpioNotifyBegin + {PI_CMD_NC, "NC", 112, 0}, // gpioNotifyClose + {PI_CMD_NO, "NO", 101, 2}, // gpioNotifyOpen + {PI_CMD_NP, "NP", 112, 0}, // gpioNotifyPause + + {PI_CMD_PARSE, "PARSE", 115, 2}, // cmdParseScript + + {PI_CMD_PFG, "PFG", 112, 2}, // gpioGetPWMfrequency + {PI_CMD_PFS, "PFS", 121, 2}, // gpioSetPWMfrequency + + {PI_CMD_PIGPV, "PIGPV", 101, 4}, // gpioVersion + + {PI_CMD_PRG, "PRG", 112, 2}, // gpioGetPWMrangeg + + {PI_CMD_PROC, "PROC", 115, 2}, // gpioStoreScript + {PI_CMD_PROCD, "PROCD", 112, 2}, // gpioDeleteScript + {PI_CMD_PROCP, "PROCP", 112, 7}, // gpioScriptStatus + {PI_CMD_PROCR, "PROCR", 191, 2}, // gpioRunScript + {PI_CMD_PROCS, "PROCS", 112, 2}, // gpioStopScript + + {PI_CMD_PRRG, "PRRG", 112, 2}, // gpioGetPWMrealRange + {PI_CMD_PRS, "PRS", 121, 2}, // gpioSetPWMrange + + {PI_CMD_PUD, "PUD", 126, 0}, // gpioSetPullUpDown + + {PI_CMD_PWM, "P", 121, 0}, // gpioPWM + {PI_CMD_PWM, "PWM", 121, 0}, // gpioPWM + + {PI_CMD_READ, "R", 112, 2}, // gpioRead + {PI_CMD_READ, "READ", 112, 2}, // gpioRead + + {PI_CMD_SERRB, "SERRB", 112, 2}, // serReadByte + {PI_CMD_SERWB, "SERWB", 121, 0}, // serWriteByte + {PI_CMD_SERC, "SERC", 112, 0}, // serClose + {PI_CMD_SERDA, "SERDA", 112, 2}, // serDataAvailable + {PI_CMD_SERO, "SERO", 132, 2}, // serOpen + {PI_CMD_SERR, "SERR", 121, 6}, // serRead + {PI_CMD_SERW, "SERW", 193, 0}, // serWrite + + {PI_CMD_SERVO, "S", 121, 0}, // gpioServo + {PI_CMD_SERVO, "SERVO", 121, 0}, // gpioServo + + {PI_CMD_SLR, "SLR", 121, 6}, // gpioSerialRead + {PI_CMD_SLRC, "SLRC", 112, 2}, // gpioSerialReadClose + {PI_CMD_SLRO, "SLRO", 121, 2}, // gpioSerialReadOpen + + {PI_CMD_SPIC, "SPIC", 112, 0}, // spiClose + {PI_CMD_SPIO, "SPIO", 131, 2}, // spiOpen + {PI_CMD_SPIR, "SPIR", 121, 6}, // spiRead + {PI_CMD_SPIW, "SPIW", 193, 2}, // spiWrite + {PI_CMD_SPIX, "SPIX", 193, 6}, // spiXfer + + {PI_CMD_TICK, "T", 101, 4}, // gpioTick + {PI_CMD_TICK, "TICK", 101, 4}, // gpioTick + + {PI_CMD_TRIG, "TRIG", 131, 0}, // gpioTrigger + + {PI_CMD_WDOG, "WDOG", 121, 0}, // gpioSetWatchdog + + {PI_CMD_WRITE, "W", 121, 0}, // gpioWrite + {PI_CMD_WRITE, "WRITE", 121, 0}, // gpioWrite + + {PI_CMD_WVAG, "WVAG", 192, 2}, // gpioWaveAddGeneric + {PI_CMD_WVAS, "WVAS", 196, 2}, // gpioWaveAddSerial + {PI_CMD_WVBSY, "WVBSY", 101, 2}, // gpioWaveTxBusy + {PI_CMD_WVCLR, "WVCLR", 101, 0}, // gpioWaveClear + {PI_CMD_WVCRE, "WVCRE", 101, 2}, // gpioWaveCreate + {PI_CMD_WVDEL, "WVDEL", 112, 2}, // gpioWaveDelete + {PI_CMD_WVGO, "WVGO" , 101, 2}, // gpioWaveTxStart + {PI_CMD_WVGOR, "WVGOR", 101, 2}, // gpioWaveTxStart + {PI_CMD_WVHLT, "WVHLT", 101, 2}, // gpioWaveTxStop + {PI_CMD_WVNEW, "WVNEW", 101, 2}, // gpioWaveAddNew + {PI_CMD_WVSC, "WVSC", 112, 2}, // gpioWaveGet*Cbs + {PI_CMD_WVSM, "WVSM", 112, 2}, // gpioWaveGet*Micros + {PI_CMD_WVSP, "WVSP", 112, 2}, // gpioWaveGet*Pulses + {PI_CMD_WVTX, "WVTX", 112, 2}, // gpioWaveTxSend + {PI_CMD_WVTXR, "WVTXR", 112, 2}, // gpioWaveTxSend {PI_CMD_ADD , "ADD" , 111, 0}, {PI_CMD_AND , "AND" , 111, 0}, {PI_CMD_CALL , "CALL" , 114, 0}, + {PI_CMD_CMDR ,"CMDR" , 111, 0}, + {PI_CMD_CMDW , "CMDW" , 111, 0}, {PI_CMD_CMP , "CMP" , 111, 0}, {PI_CMD_DCR , "DCR" , 113, 0}, {PI_CMD_DCRA , "DCRA" , 101, 0}, @@ -122,8 +183,10 @@ cmdInfo_t cmdInfo[]= {PI_CMD_JZ , "JZ" , 114, 0}, {PI_CMD_LD , "LD" , 123, 0}, {PI_CMD_LDA , "LDA" , 111, 0}, + {PI_CMD_LDAB , "LDAB" , 111, 0}, {PI_CMD_MLT , "MLT" , 111, 0}, {PI_CMD_MOD , "MOD" , 111, 0}, + {PI_CMD_NOP , "NOP" , 101, 0}, {PI_CMD_OR , "OR" , 111, 0}, {PI_CMD_POP , "POP" , 113, 0}, {PI_CMD_POPA , "POPA" , 101, 0}, @@ -135,6 +198,7 @@ cmdInfo_t cmdInfo[]= {PI_CMD_RR , "RR" , 123, 0}, {PI_CMD_RRA , "RRA" , 111, 0}, {PI_CMD_STA , "STA" , 113, 0}, + {PI_CMD_STAB , "STAB" , 111, 0}, {PI_CMD_SUB , "SUB" , 111, 0}, {PI_CMD_SYS , "SYS" , 116, 0}, {PI_CMD_TAG , "TAG" , 114, 0}, @@ -145,87 +209,150 @@ cmdInfo_t cmdInfo[]= }; + char * cmdUsage = "\ -BC1 v Clear gpios specified by mask v in bank 1.\n\ -BC2 v Clear gpios specified by mask v in bank 2.\n\ -BR1 Read gpios bank 1.\n\ -BR2 Read gpios bank 2.\n\ -BS1 v Set gpios specified by mask v in bank 1.\n\ -BS2 v Set gpios specified by mask v in bank 2.\n\ -H Displays command help.\n\ -HELP Displays command help.\n\ -HWVER Return hardware version.\n\ -M g m Set gpio g to mode m.\n\ -MG g Get gpio g mode.\n\ -MICS v Delay for v microseconds.\n\ -MILS v Delay for v milliseconds.\n\ -MODEG g Get gpio g mode.\n\ -MODES g m Set gpio g to mode m.\n\ -NB h v Start notifications on handle h for gpios specified by mask v.\n\ -NC h Close notification handle h.\n\ -NO Request notification handle.\n\ -NP h Pause notifications on handle h.\n\ -P u v Set PWM value for user gpio u to v.\n\ -PARSE t Validate script text t without storing.\n\ -PFG u Get PWM frequency for user gpio u.\n\ -PFS u v Set PWM frequency for user gpio u to v.\n\ -PIGPV Return pigpio version.\n\ -PRG u Get PWM range for user gpio u.\n\ -PROC t Store text t of script.\n\ -PROCD s Delete script s.\n\ -PROCP s Get current status and parameter values for script s.\n\ -PROCR s pars Run script s with up to 10 optional parameters.\n\ -PROCS s Stop script s.\n\ -PRRG u Get PWM real range for user gpio u.\n\ -PRS u v Set PWM range for user gpio u to v.\n\ -PUD g p Set gpio pull up/down for gpio g to p.\n\ -PWM u v Set PWM value for user gpio u to v.\n\ -R g Read gpio g.\n\ -READ g Read gpio g.\n\ -S u v Set servo value for user gpio u to v microseconds.\n\ -SERVO u v Set servo value for user gpio u to v microseconds.\n\ -SLR u v Read up to d bytes of serial data from user gpio u.\n\ -SLRC u Close user gpio u for serial data.\n\ -SLRO u b Open user gpio u for serial data at b baud.\n\ -T Return current tick.\n\ -TICK Return current tick.\n\ -TRIG u pl L Trigger level L for pl micros on user gpio u.\n\ -W g L Write level L to gpio g.\n\ -WDOG u v Set watchdog of v milliseconds on user gpio u.\n\ -WRITE g L Write level L to gpio g.\n\ -WVAG pulses Wave add generic pulses.\n\ -WVAS u b o t Wave add serial data t to user gpio u at b baud.\n\ -WVBSY Check if wave busy.\n\ -WVCLR Wave clear.\n\ -WVCRE Create wave from added pulses.\n\ -WVDEL w Delete waves w and higher.\n\ -WVGO Wave transmit (DEPRECATED).\n\ -WVGOR Wave transmit repeatedly (DEPRECATED).\n\ -WVHLT Wave stop.\n\ -WVNEW Start a new empty wave.\n\ -WVSC ws Wave get DMA control block stats.\n\ -WVSM ws Wave get micros stats.\n\ -WVSP ws Wave get pulses stats.\n\ -WVTX w Transmit wave w as one-shot.\n\ -WVTXR w Transmit wave w repeatedly.\n\ +BC1 bits Clear specified gpios in bank 1.\n\ +BC2 bits Clear specified gpios in bank 2.\n\ +BR1 Read bank 1 gpios.\n\ +BR2 Read bank 2 gpios.\n\ +BS1 bits Set specified gpios in bank 2.\n\ +BS2 bits Set specified gpios in bank 2.\n\ \n\ -b = baud rate.\n\ -g = any gpio (0-53).\n\ -h = handle (>=0).\n\ -L = level (0-1).\n\ -m = mode (RW540123).\n\ -mask = a bit mask where (1<=0).\n\ -p = pud (ODU).\n\ -pars = 0 to 10 parameters for script.\n\ -pl = pulse length (1-50).\n\ -pulses = 1 or more triplets of gpios on, gpios off, delay.\n\ -s = script id (>=0).\n\ -t = text.\n\ -u = user gpio (0-31).\n\ -v = value.\n\ -w = wave id (>=0).\n\ -ws = 0=now, 1=high, 2=max.\n\ +H/HELP Display command help.\n\ +\n\ +HWVER Get hardware version.\n\ +\n\ +I2CC h Close I2C handle.\n\ +I2CO ib id if Open I2C bus and device with flags.\n\ +\n\ +I2CPC h r wv smb Process Call: exchange register with word.\n\ +I2CPK h r bvs smb Block Process Call: exchange data bytes with register.\n\ +\n\ +I2CRB h r smb Read Byte Data: read byte from register.\n\ +I2CRD h num i2c Read bytes.\n\ +I2CRI h r num smb Read I2C Block Data: read bytes from register.\n\ +I2CRK h r smb Read Block Data: read data from register.\n\ +I2CRS h smb Read Byte: read byte.\n\ +I2CRW h r smb Read Word Data: read word from register.\n\ +\n\ +I2CWB h r bv smb Write Byte Data: write byte to register.\n\ +I2CWD h bvs i2c Write data.\n\ +I2CWI h smb Write I2C Block Data.\n\ +I2CWK h r bvs smb Write Block Data: write data to register.\n\ +I2CWQ h bit smb Write Quick: write bit.\n\ +I2CWS h bv smb Write Byte: write byte.\n\ +I2CWW h r wv smb Write Word Data: write word to register.\n\ +\n\ +M/MODES g m Set gpio mode.\n\ +MG/MODEG g Get gpio mode.\n\ +\n\ +MICS v Delay for microseconds.\n\ +MILS v Delay for milliseconds.\n\ +\n\ +NB h bits Start notification.\n\ +NC h Close notification.\n\ +NO Request a notification.\n\ +NP h Pause notification.\n\ +\n\ +P/PWM u v Set gpio PWM value.\n\ +\n\ +PARSE t Validate script.\n\ +\n\ +PFG u Get gpio PWM frequency.\n\ +PFS u v Set gpio PWM frequency.\n\ +\n\ +PIGPV Get pigpio library version.\n\ +\n\ +PRG u Get gpio PWM range.\n\ +\n\ +PROC t Store script.\n\ +PROCD sid Delete script.\n\ +PROCP sid Get script status and parameters.\n\ +PROCR sid pars Run script.\n\ +PROCS sid Stop script.\n\ +\n\ +PRRG u Get gpio PWM real range.\n\ +PRS u v Set gpio PWM range.\n\ +\n\ +PUD g p Set gpio pull up/down.\n\ +\n\ +R/READ g Read gpio level.\n\ +\n\ +S/SERVO u v Set gpio servo pulsewidth.\n\ +\n\ +SERC h Close serial handle.\n\ +SERDA h Check for serial data ready to read.\n\ +SERO srd srb srf Open serial device at baud with flags.\n\ +\n\ +SERR h num Read bytes from serial handle.\n\ +SERRB Read byte from serial handle.\n\ +SERW h bvs Write bytes to serial handle.\n\ +SERWB h bv Write byte to serial handle.\n\ +\n\ +SLR u num Read bit bang serial data from gpio.\n\ +SLRC u Close gpio for bit bang serial data.\n\ +SLRO u b Open gpio for bit bang serial data.\n\ +\n\ +SPIC h SPI close handle.\n\ +SPIO sc sb sf SPI open channel at baud with flags.\n\ +SPIR h num SPI read bytes from handle.\n\ +SPIW h bvs SPI write bytes to handle.\n\ +SPIX h bvs SPI transfer bytes to handle.\n\ +\n\ +T/TICK Get current tick.\n\ +\n\ +TRIG u pl L Trigger level for micros on gpio.\n\ +\n\ +W/WRITE g L Write level to gpio.\n\ +\n\ +WDOG u v Set millisecond watchdog on gpio.\n\ +\n\ +WVAG trips Wave add generic pulses.\n\ +WVAS u b o bvs Wave add serial data with offset for gpio at baud.\n\ +WVBSY Check if wave busy.\n\ +WVCLR Wave clear.\n\ +WVCRE Create wave from added pulses.\n\ +WVDEL wid Delete waves w and higher.\n\ +WVGO Wave transmit (DEPRECATED).\n\ +WVGOR Wave transmit repeatedly (DEPRECATED).\n\ +WVHLT Wave stop.\n\ +WVNEW Start a new empty wave.\n\ +WVSC ws Wave get DMA control block stats.\n\ +WVSM ws Wave get micros stats.\n\ +WVSP ws Wave get pulses stats.\n\ +WVTX wid Transmit wave as one-shot.\n\ +WVTXR wid Transmit wave repeatedly.\n\ +\n\ +bits = a mask where (1<=0).\n\ +ib = I2C bus (0-1).\n\ +id = I2C device (0-127).\n\ +if = I2C flags (0).\n\ +L = level (0-1).\n\ +m = mode (RW540123).\n\ +num = number of bytes to read.\n\ +o = offset (>=0).\n\ +p = pud (ODU).\n\ +pars = 0 to 10 parameters for script.\n\ +pl = pulse length (1-50).\n\ +r = register.\n\ +sid = script id (>=0).\n\ +sb = SPI baud.\n\ +sc = SPI channel (0-1).\n\ +sf = SPI flags (0-3).\n\ +srd = serial device (/dev/tty*).\n\ +srb = serial baud rate.\n\ +srf = serial flags (0).\n\ +t = text.\n\ +trips = 1 or more triplets of gpios on, gpios off, delay.\n\ +u = user gpio (0-31).\n\ +v = value.\n\ +w = wave id (>=0).\n\ +ws = 0=now, 1=high, 2=max.\n\ +wv = word value (0-65535).\n\ \n\ Numbers may be entered as hex (prefix 0x), octal (prefix 0),\n\ otherwise they are assumed to be decimal.\n\ @@ -309,6 +436,24 @@ static errInfo_t errInfo[]= {PI_TOO_MANY_OOL , "No more OOL for waveform"}, {PI_EMPTY_WAVEFORM , "attempt to create an empty waveform"}, {PI_NO_WAVEFORM_ID , "no more waveform ids"}, + {PI_I2C_OPEN_FAILED , "can't open I2C device"}, + {PI_SER_OPEN_FAILED , "can't open serial device"}, + {PI_SPI_OPEN_FAILED , "can't open SPI device"}, + {PI_BAD_I2C_BUS , "bad I2C bus"}, + {PI_BAD_I2C_ADDR , "bad I2C address"}, + {PI_BAD_SPI_CHANNEL , "bad SPI channel"}, + {PI_BAD_FLAGS , "bad i2c/spi/ser open flags"}, + {PI_BAD_SPI_SPEED , "bad SPI speed"}, + {PI_BAD_SER_DEVICE , "bad serial device name"}, + {PI_BAD_SER_SPEED , "bad serial baud rate"}, + {PI_BAD_PARAM , "bad i2c/spi/ser parameter"}, + {PI_I2C_WRITE_FAILED , "I2C write failed"}, + {PI_I2C_READ_FAILED , "I2C read failed"}, + {PI_BAD_SPI_COUNT , "bad SPI count"}, + {PI_SER_WRITE_FAILED , "ser write failed"}, + {PI_SER_READ_FAILED , "ser read failed"}, + {PI_SER_READ_NO_DATA , "ser read no data available"}, + {PI_UNKNOWN_COMMAND , "unknown command"}, }; @@ -372,12 +517,18 @@ char *cmdStr(void) return intCmdStr; } -int cmdParse(char *buf, uint32_t *p, void **v, cmdCtlParse_t *ctl) +int cmdParse( + char *buf, uint32_t *p, unsigned ext_len, char *ext, cmdCtlParse_t *ctl) { int f, valid, idx, val, pp, pars, n, n2, i; - char *ptr; + char *p8; + int32_t *p32; char c; - int32_t param[MAX_PARAM]; + uint32_t tp1; + int8_t to1; + + /* Check that ext is big enough for the largest message. */ + if (ext_len < (4 * CMD_MAX_PARAM)) return CMD_EXT_TOO_SMALL; bzero(&ctl->opt, sizeof(ctl->opt)); @@ -394,12 +545,14 @@ int cmdParse(char *buf, uint32_t *p, void **v, cmdCtlParse_t *ctl) valid = 0; p[0] = cmdInfo[idx].cmd; - p[1] = 0; - p[2] = 0; + p[1] = 0; + p[2] = 0; + p[3] = 0; switch (cmdInfo[idx].vt) { - case 101: /* BR1 BR2 DCRA H HALT HELP HWVER INRA NO + case 101: /* BR1 BR2 H HELP HWVER + DCRA HALT INRA NO PIGPV POPA PUSHA RET T TICK WVBSY WVCLR WVCRE WVGO WVGOR WVHLT WVNEW @@ -409,26 +562,28 @@ int cmdParse(char *buf, uint32_t *p, void **v, cmdCtlParse_t *ctl) break; - case 111: /* ADD AND BC1 BC2 BS1 BS2 CMP DIV LDA MLT - MOD OR RLA RRA SUB WAIT XOR + case 111: /* BC1 BC2 BS1 BS2 + ADD AND CMP DIV LDA LDAB MLT + MOD OR RLA RRA STAB SUB WAIT XOR One parameter, any value. */ - ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[0]); + ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[1]); - if (ctl->opt[0] > 0) valid = 1; + if (ctl->opt[1] > 0) valid = 1; break; - case 112: /* MG MICS MILS MODEG NC NP PFG PRG - PROCD PROCP PROCS PRRG R READ SLRC + case 112: /* I2CC + I2CRB MG MICS MILS MODEG NC NP PFG PRG + PROCD PROCP PROCS PRRG R READ SLRC SPIC WVDEL WVSC WVSM WVSP WVTX WVTXR One positive parameter. */ - ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[0]); + ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[1]); - if ((ctl->opt[0] > 0) && ((int)p[1] >= 0)) valid = 1; + if ((ctl->opt[1] > 0) && ((int)p[1] >= 0)) valid = 1; break; @@ -436,9 +591,9 @@ int cmdParse(char *buf, uint32_t *p, void **v, cmdCtlParse_t *ctl) One register parameter. */ - ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[0]); + ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[1]); - if ((ctl->opt[0] > 0) && (p[1] < PI_MAX_SCRIPT_VARS)) valid = 1; + if ((ctl->opt[1] > 0) && (p[1] < PI_MAX_SCRIPT_VARS)) valid = 1; break; @@ -446,8 +601,8 @@ int cmdParse(char *buf, uint32_t *p, void **v, cmdCtlParse_t *ctl) One numeric parameter, any value. */ - ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[0]); - if (ctl->opt[0] == CMD_NUMERIC) valid = 1; + ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[1]); + if (ctl->opt[1] == CMD_NUMERIC) valid = 1; break; @@ -455,10 +610,9 @@ int cmdParse(char *buf, uint32_t *p, void **v, cmdCtlParse_t *ctl) One parameter, string (rest of input). */ - p[1] = strlen(buf+ctl->eaten); - v[1] = buf+ctl->eaten; - ctl->eaten += p[1]; - + p[3] = strlen(buf+ctl->eaten); + memcpy(ext, buf+ctl->eaten, p[3]); + ctl->eaten += p[3]; valid = 1; break; @@ -485,24 +639,25 @@ int cmdParse(char *buf, uint32_t *p, void **v, cmdCtlParse_t *ctl) if (valid) { - p[1] = n; - ctl->opt[0] = CMD_NUMERIC; - v[1]=buf+ctl->eaten; + p[3] = n; + ctl->opt[3] = CMD_NUMERIC; + memcpy(ext, buf+ctl->eaten, n); ctl->eaten += n2; } } break; - case 121: /* P PFS PRS PWM S SERVO SLR SLRO W WDOG WRITE + case 121: /* I2CRD I2CRR I2CRW I2CWB I2CWQ P PFS PRS + PWM S SERVO SLR SLRO W WDOG WRITE Two positive parameters. */ - ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[0]); - ctl->eaten += getNum(buf+ctl->eaten, &p[2], &ctl->opt[1]); + ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[1]); + ctl->eaten += getNum(buf+ctl->eaten, &p[2], &ctl->opt[2]); - if ((ctl->opt[0] > 0) && ((int)p[1] >= 0) && - (ctl->opt[1] > 0) && ((int)p[2] >= 0)) valid = 1; + if ((ctl->opt[1] > 0) && ((int)p[1] >= 0) && + (ctl->opt[2] > 0) && ((int)p[2] >= 0)) valid = 1; break; @@ -510,11 +665,11 @@ int cmdParse(char *buf, uint32_t *p, void **v, cmdCtlParse_t *ctl) Two parameters, first positive, second any value. */ - ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[0]); - ctl->eaten += getNum(buf+ctl->eaten, &p[2], &ctl->opt[1]); + ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[1]); + ctl->eaten += getNum(buf+ctl->eaten, &p[2], &ctl->opt[2]); - if ((ctl->opt[0] > 0) && ((int)p[1] >= 0) && - (ctl->opt[1] > 0)) valid = 1; + if ((ctl->opt[1] > 0) && ((int)p[1] >= 0) && + (ctl->opt[2] > 0)) valid = 1; break; @@ -522,12 +677,12 @@ int cmdParse(char *buf, uint32_t *p, void **v, cmdCtlParse_t *ctl) Two parameters, first register, second any value. */ - ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[0]); - ctl->eaten += getNum(buf+ctl->eaten, &p[2], &ctl->opt[1]); + ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[1]); + ctl->eaten += getNum(buf+ctl->eaten, &p[2], &ctl->opt[2]); - if ((ctl->opt[0] > 0) && + if ((ctl->opt[1] > 0) && (p[1] < PI_MAX_SCRIPT_VARS) && - (ctl->opt[1] > 0)) valid = 1; + (ctl->opt[2] > 0)) valid = 1; break; @@ -535,11 +690,11 @@ int cmdParse(char *buf, uint32_t *p, void **v, cmdCtlParse_t *ctl) Two register parameters. */ - ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[0]); - ctl->eaten += getNum(buf+ctl->eaten, &p[2], &ctl->opt[1]); + ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[1]); + ctl->eaten += getNum(buf+ctl->eaten, &p[2], &ctl->opt[2]); - if ((ctl->opt[0] > 0) && (p[1] < PI_MAX_SCRIPT_VARS) && - (ctl->opt[1] > 0) && (p[2] < PI_MAX_SCRIPT_VARS)) valid = 1; + if ((ctl->opt[1] > 0) && (p[1] < PI_MAX_SCRIPT_VARS) && + (ctl->opt[2] > 0) && (p[2] < PI_MAX_SCRIPT_VARS)) valid = 1; break; @@ -547,19 +702,19 @@ int cmdParse(char *buf, uint32_t *p, void **v, cmdCtlParse_t *ctl) Two parameters, first positive, second in 'RW540123'. */ - ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[0]); + ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[1]); f = sscanf(buf+ctl->eaten, " %c %n", &c, &n); - if ((ctl->opt[0] > 0) && ((int)p[1] >= 0) && (f >= 1)) + if ((ctl->opt[1] > 0) && ((int)p[1] >= 0) && (f >= 1)) { ctl->eaten += n; val = toupper(c); - ptr = strchr(fmtMdeStr, val); + p8 = strchr(fmtMdeStr, val); - if (ptr != NULL) + if (p8 != NULL) { - val = ptr - fmtMdeStr; + val = p8 - fmtMdeStr; p[2] = val; valid = 1; } @@ -571,18 +726,18 @@ int cmdParse(char *buf, uint32_t *p, void **v, cmdCtlParse_t *ctl) Two parameters, first positive, second in 'ODU'. */ - ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[0]); + ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[1]); f = sscanf(buf+ctl->eaten, " %c %n", &c, &n); - if ((ctl->opt[0] > 0) && ((int)p[1] >= 0) && (f >= 1)) + if ((ctl->opt[1] > 0) && ((int)p[1] >= 0) && (f >= 1)) { ctl->eaten += n; val = toupper(c); - ptr = strchr(fmtPudStr, val); - if (ptr != NULL) + p8 = strchr(fmtPudStr, val); + if (p8 != NULL) { - val = ptr - fmtPudStr; + val = p8 - fmtPudStr; p[2] = val; valid = 1; } @@ -590,38 +745,43 @@ int cmdParse(char *buf, uint32_t *p, void **v, cmdCtlParse_t *ctl) break; - case 131: /* TRIG + case 131: /* I2CO I2CPC I2CRI I2CWB I2CWW SPIO TRIG Three positive parameters. */ - ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[0]); - ctl->eaten += getNum(buf+ctl->eaten, &p[2], &ctl->opt[1]); - ctl->eaten += getNum(buf+ctl->eaten, &p[3], &ctl->opt[2]); + ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[1]); + ctl->eaten += getNum(buf+ctl->eaten, &p[2], &ctl->opt[2]); + ctl->eaten += getNum(buf+ctl->eaten, &tp1, &to1); - if ((ctl->opt[0] > 0) && ((int)p[1] >= 0) && - (ctl->opt[1] > 0) && ((int)p[2] >= 0) && - (ctl->opt[2] == CMD_NUMERIC) && ((int)p[3] >= 0)) + if ((ctl->opt[1] > 0) && ((int)p[1] >= 0) && + (ctl->opt[2] > 0) && ((int)p[2] >= 0) && + (to1 == CMD_NUMERIC) && ((int)tp1 >= 0)) + { + p[3] = 4; + memcpy(ext, &tp1, 4); valid = 1; + } break; - case 141: /* WVAS + case 132: /* SERO - Four parameters, first two positive, third any value, - last string (rest of input). + Three parameters, first a string, rest >=0 */ - ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[0]); - ctl->eaten += getNum(buf+ctl->eaten, &p[2], &ctl->opt[1]); - ctl->eaten += getNum(buf+ctl->eaten, &p[3], &ctl->opt[2]); - - if ((ctl->opt[0] == CMD_NUMERIC) && ((int)p[1] >= 0) && - (ctl->opt[1] == CMD_NUMERIC) && ((int)p[2] >= 0) && - (ctl->opt[2] == CMD_NUMERIC)) + f = sscanf(buf+ctl->eaten, " %*s%n %n", &n, &n2); + if ((f >= 0) && n) { - p[4] = strlen(buf+ctl->eaten); - v[1] = buf+ctl->eaten; - ctl->eaten += p[4]; - valid = 1; + p[3] = n; + ctl->opt[2] = CMD_NUMERIC; + memcpy(ext, buf+ctl->eaten, n); + ctl->eaten += n2; + + ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[1]); + ctl->eaten += getNum(buf+ctl->eaten, &p[2], &ctl->opt[2]); + + if ((ctl->opt[1] > 0) && ((int)p[1] >= 0) && + (ctl->opt[2] > 0) && ((int)p[2] >= 0)) + valid = 1; } break; @@ -631,22 +791,25 @@ int cmdParse(char *buf, uint32_t *p, void **v, cmdCtlParse_t *ctl) One to 11 parameters, first positive, optional remainder, any value. */ - ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[0]); + ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[1]); - if ((ctl->opt[0] == CMD_NUMERIC) && ((int)p[1] >= 0)) + if ((ctl->opt[1] == CMD_NUMERIC) && ((int)p[1] >= 0)) { pars = 0; + p32 = (int32_t *)ext; while (pars < PI_MAX_SCRIPT_PARAMS) { - ctl->eaten += getNum(buf+ctl->eaten, &p[2], &ctl->opt[1]); - if (ctl->opt[1] == CMD_NUMERIC) param[pars++] = p[2]; + ctl->eaten += getNum(buf+ctl->eaten, &tp1, &to1); + if (to1 == CMD_NUMERIC) + { + pars++; + *p32++ = tp1; + } else break; } - p[2] = pars; - - v[1] = param; + p[3] = pars * 4; valid = 1; } @@ -658,23 +821,133 @@ int cmdParse(char *buf, uint32_t *p, void **v, cmdCtlParse_t *ctl) One or more triplets (gpios on, gpios off, delay), any value. */ - pars = 0; - while (pars < MAX_PARAM) + pars = 0; + p32 = (int32_t *)ext; + + while (pars < CMD_MAX_PARAM) { - ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[0]); - if (ctl->opt[0] == CMD_NUMERIC) param[pars++] = p[1]; + ctl->eaten += getNum(buf+ctl->eaten, &tp1, &to1); + if (to1 == CMD_NUMERIC) + { + pars++; + *p32++ = tp1; + } else break; } - p[1] = pars / 3; - - v[1] = param; + p[3] = pars * 4; if (pars && ((pars % 3) == 0)) valid = 1; break; + case 193: /* I2CWD SERW + + Two or more parameters, first >=0, rest 0-255. + */ + ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[1]); + + if ((ctl->opt[1] == CMD_NUMERIC) && ((int)p[1] >= 0)) + { + pars = 0; + p8 = ext; + + while (pars < CMD_MAX_PARAM) + { + ctl->eaten += getNum(buf+ctl->eaten, &tp1, &to1); + if ((to1 == CMD_NUMERIC) && + ((int)tp1>=0) && ((int)tp1<=255)) + { + pars++; + *p8++ = tp1; + } + else break; + } + + p[3] = pars; + + if (pars) valid = 1; + } + + break; + + case 194: /* I2CPK I2CWI I2CWK + + Three to 34 parameters, all 0-255. + */ + + ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[1]); + ctl->eaten += getNum(buf+ctl->eaten, &p[2], &ctl->opt[2]); + + if ((ctl->opt[1] == CMD_NUMERIC) && + (ctl->opt[2] == CMD_NUMERIC) && + ((int)p[1]>=0) && ((int)p[2]>=0) && ((int)p[2]<=255)) + { + pars = 0; + p8 = ext; + + while (pars < 32) + { + ctl->eaten += getNum(buf+ctl->eaten, &tp1, &to1); + if ((to1 == CMD_NUMERIC) && + ((int)tp1>=0) && + ((int)tp1<=255)) + { + pars++; + *p8++ = tp1; + } + else break; + } + + p[3] = pars; + + if (pars > 0) valid = 1; + } + + break; + + case 196: /* WVAS + + gpio baud offset char... + + p1 gpio + p2 baud + p3 len + 4 + --------- + uint32_t offset + uint8_t[len] + */ + ctl->eaten += getNum(buf+ctl->eaten, &p[1], &ctl->opt[1]); + ctl->eaten += getNum(buf+ctl->eaten, &p[2], &ctl->opt[2]); + ctl->eaten += getNum(buf+ctl->eaten, &tp1, &to1); + + if ((ctl->opt[1] == CMD_NUMERIC) && ((int)p[1] >= 0) && + (ctl->opt[2] == CMD_NUMERIC) && ((int)p[2] > 0) && + (to1 == CMD_NUMERIC)) + { + pars = 0; + + memcpy(ext, &tp1, 4); + p8 = ext + 4; + while (pars < CMD_MAX_PARAM) + { + ctl->eaten += getNum(buf+ctl->eaten, &tp1, &to1); + if ((to1 == CMD_NUMERIC) && + ((int)tp1>=0) && ((int)tp1<=255)) + { + *p8++ = tp1; + pars++; + } + else break; + } + + p[3] = pars + 4; + + if (pars > 0) valid = 1; + } + + break; } @@ -697,9 +970,9 @@ int cmdParseScript(char *script, cmdScript_t *s, int diags) int idx, len, b, i, j, tags, resolved; int status; uint32_t p[10]; - void *v[10]; cmdInstr_t instr; cmdCtlParse_t ctl; + char v[CMD_MAX_EXTENSION]; ctl.eaten = 0; @@ -714,7 +987,7 @@ int cmdParseScript(char *script, cmdScript_t *s, int diags) b = (sizeof(int) * (PI_MAX_SCRIPT_PARAMS + PI_MAX_SCRIPT_VARS)) + (sizeof(cmdInstr_t) * (len + 2) / 2) + len; - s->par = calloc(b, 1); + s->par = calloc(1, b); if (s->par == NULL) return -1; @@ -735,81 +1008,52 @@ int cmdParseScript(char *script, cmdScript_t *s, int diags) while (ctl.eaten= 0) { - switch (instr.p[0]) + if (p[3]) { - case PI_CMD_HELP: - case PI_CMD_PARSE: - case PI_CMD_PROC: - case PI_CMD_PROCD: - case PI_CMD_PROCP: - case PI_CMD_PROCR: - case PI_CMD_PROCS: - case PI_CMD_SLR: - case PI_CMD_SLRC: - case PI_CMD_SLRO: - case PI_CMD_WVAG: - case PI_CMD_WVAS: + memcpy(s->str_area + s->str_area_pos, v, p[3]); + s->str_area[s->str_area_pos + p[3]] = 0; + p[4] = (intptr_t) s->str_area + s->str_area_pos; + s->str_area_pos += (p[3] + 1); + } + memcpy(&instr.p, p, sizeof(instr.p)); + + if (instr.p[0] == PI_CMD_TAG) + { + if (tags < PI_MAX_SCRIPT_TAGS) + { + /* check tag not already used */ + for (j=0; jinstrs; + tags++; + } + else + { if (diags) { - fprintf(stderr, "Illegal command: %s\n", cmdStr()); + fprintf(stderr, "Too many tags: %d\n", instr.p[1]); } - - if (!status) status = PI_BAD_SCRIPT_CMD; + if (!status) status = PI_TOO_MANY_TAGS; idx = -1; - - break; - - case PI_CMD_TAG: - - if (tags < PI_MAX_SCRIPT_TAGS) - { - /* check tag not already used */ - for (j=0; jinstrs; - tags++; - } - else - { - if (diags) - { - fprintf(stderr, "Too many tags: %d\n", instr.p[1]); - } - if (!status) status = PI_TOO_MANY_TAGS; - idx = -1; - } - - break; - - case PI_CMD_SYS: - - strncpy(s->str_area+s->str_area_pos, v[1], p[1]); - s->str_area[s->str_area_pos+p[1]] = 0; - instr.p[1] = (intptr_t) s->str_area+s->str_area_pos; - s->str_area_pos += (p[1] + 1); - - break; - + } } } else diff --git a/command.h b/command.h index 06d0fef..fa3cd2b 100644 --- a/command.h +++ b/command.h @@ -26,7 +26,7 @@ For more information, please refer to */ /* -This version is for pigpio version 14+ +This version is for pigpio version 16+ */ #ifndef COMMAND_H @@ -37,15 +37,33 @@ This version is for pigpio version 14+ #include "pigpio.h" -#define MAX_PARAM 512 +#define CMD_MAX_PARAM 512 +#define CMD_MAX_EXTENSION 8192 #define CMD_UNKNOWN_CMD -1 #define CMD_BAD_PARAMETER -2 +#define CMD_EXT_TOO_SMALL -3 + +#define CMD_P_ARR 10 +#define CMD_V_ARR 10 #define CMD_NUMERIC 1 #define CMD_VAR 2 #define CMD_PAR 3 +typedef struct +{ + uint32_t cmd; + uint32_t p1; + uint32_t p2; + union + { + uint32_t p3; + uint32_t ext_len; + uint32_t res; + }; +} cmdCmd_t; + typedef struct { int eaten; @@ -68,7 +86,7 @@ typedef struct typedef struct { - uint32_t p[7]; + uint32_t p[5]; int8_t opt[4]; } cmdInstr_t; @@ -92,7 +110,7 @@ extern cmdInfo_t cmdInfo[]; extern char *cmdUsage; -int cmdParse(char *buf, uint32_t *p, void **v, cmdCtlParse_t *ctl); +int cmdParse(char *buf, uint32_t *p, unsigned ext_len, char *ext, cmdCtlParse_t *ctl); int cmdParseScript(char *script, cmdScript_t *s, int diags); diff --git a/pigpio.c b/pigpio.c index cd38591..68e1451 100644 --- a/pigpio.c +++ b/pigpio.c @@ -25,7 +25,7 @@ OTHER DEALINGS IN THE SOFTWARE. For more information, please refer to */ -/* pigpio version 15 */ +/* pigpio version 16 */ #include #include @@ -36,11 +36,13 @@ For more information, please refer to #include #include #include +#include #include #include #include #include #include +#include #include #include #include @@ -51,8 +53,10 @@ For more information, please refer to #include #include #include +#include #include "pigpio.h" + #include "command.h" /* --------------------------------------------------------------- */ @@ -538,6 +542,15 @@ bit 0 READ_LAST_NOT_SET_ERROR #define TICKSLOTS 50 +#define PI_I2C_CLOSED 0 +#define PI_I2C_OPENED 1 + +#define PI_SPI_CLOSED 0 +#define PI_SPI_OPENED 1 + +#define PI_SER_CLOSED 0 +#define PI_SER_OPENED 1 + #define PI_NOTIFY_CLOSED 0 #define PI_NOTIFY_CLOSING 1 #define PI_NOTIFY_OPENED 2 @@ -555,10 +568,28 @@ bit 0 READ_LAST_NOT_SET_ERROR #define MAX_EMITS (PIPE_BUF / sizeof(gpioReport_t)) #define SRX_BUF_SIZE 8192 -#define CMD_BUF_SIZE 4096 #define MAX_DELAY 50 +#define PI_I2C_SLAVE 0x0703 +#define PI_I2C_SMBUS 0x0720 + +#define PI_I2C_SMBUS_READ 1 +#define PI_I2C_SMBUS_WRITE 0 + +#define PI_I2C_SMBUS_QUICK 0 +#define PI_I2C_SMBUS_BYTE 1 +#define PI_I2C_SMBUS_BYTE_DATA 2 +#define PI_I2C_SMBUS_WORD_DATA 3 +#define PI_I2C_SMBUS_PROC_CALL 4 +#define PI_I2C_SMBUS_BLOCK_DATA 5 +#define PI_I2C_SMBUS_I2C_BLOCK_BROKEN 6 +#define PI_I2C_SMBUS_BLOCK_PROC_CALL 7 +#define PI_I2C_SMBUS_I2C_BLOCK_DATA 8 + +#define PI_I2C_SMBUS_BLOCK_MAX 32 +#define PI_I2C_SMBUS_I2C_BLOCK_MAX 32 + /* --------------------------------------------------------------- */ typedef void (*callbk_t) (); @@ -677,6 +708,28 @@ typedef struct int pipe; } gpioNotify_t; +typedef struct +{ + uint16_t state; + int16_t fd; + uint32_t flags; +} i2cInfo_t; + +typedef struct +{ + uint16_t state; + int16_t fd; + uint32_t flags; +} serInfo_t; + +typedef struct +{ + uint16_t state; + int16_t fd; + unsigned speed; + uint32_t flags; +} spiInfo_t; + typedef struct { uint32_t startTick; @@ -738,12 +791,33 @@ typedef struct typedef struct { - int botCB; /* first CB used by wave */ - int topCB; /* last CB used by wave */ - int botOOL; - int topOOL; + uint16_t botCB; /* first CB used by wave */ + uint16_t topCB; /* last CB used by wave */ + uint16_t botOOL; + uint16_t topOOL; } waveInfo_t; +union my_smbus_data +{ + uint8_t byte; + uint16_t word; + uint8_t block[PI_I2C_SMBUS_BLOCK_MAX + 2]; +}; + +struct my_smbus_ioctl_data +{ + uint8_t read_write; + uint8_t command; + uint32_t size; + union my_smbus_data *data; +}; + +struct my_rdwr_ioctl_data +{ + struct i2c_msg *msgs; /* pointers to msgs */ + uint32_t nmsgs; /* number of msgs */ +}; + /* --------------------------------------------------------------- */ /* initialise once then preserve */ @@ -818,6 +892,10 @@ static gpioInfo_t gpioInfo [PI_MAX_USER_GPIO+1]; static gpioNotify_t gpioNotify [PI_NOTIFY_SLOTS]; +static i2cInfo_t i2cInfo [PI_I2C_SLOTS]; +static serInfo_t serInfo [PI_SER_SLOTS]; +static spiInfo_t spiInfo [PI_SPI_SLOTS]; + static gpioScript_t gpioScript [PI_MAX_SCRIPTS]; static gpioSignal_t gpioSignal [PI_MAX_SIGNUM+1]; @@ -906,6 +984,36 @@ static int gpioNotifyOpenInBand(int fd); /* ======================================================================= */ +static int my_smbus_access( + int fd, char rw, uint8_t cmd, int size, union my_smbus_data *data) +{ + struct my_smbus_ioctl_data args; + + args.read_write = rw; + args.command = cmd; + args.size = size; + args.data = data; + + return ioctl(fd, PI_I2C_SMBUS, &args); +} + +static char *myBuf2Str(unsigned count, char *buf) +{ + static char str[64]; + int i, c; + + if (count) + { + if (count > 10) c = 10; else c = count; + + for (i=0; i bufSize) p[2] = bufSize; + res = i2cReadDevice(p[1], buf, p[2]); + break; + + case PI_CMD_I2CRI: + memcpy(&p[4], buf, 4); + res = i2cReadI2CBlockData(p[1], p[2], buf, p[4]); + break; + + case PI_CMD_I2CRK: + res = i2cReadBlockData(p[1], p[2], buf); + break; + + case PI_CMD_I2CRS: res = i2cReadByte(p[1]); break; + + case PI_CMD_I2CRW: res = i2cReadWordData(p[1], p[2]); break; + + case PI_CMD_I2CWB: + memcpy(&p[4], buf, 4); + res = i2cWriteByteData(p[1], p[2], p[4]); + break; + + case PI_CMD_I2CWD: + res = i2cWriteDevice(p[1], buf, p[3]); + break; + + case PI_CMD_I2CWI: + res = i2cWriteI2CBlockData(p[1], p[2], buf, p[3]); + break; + + case PI_CMD_I2CWK: + res = i2cWriteBlockData(p[1], p[2], buf, p[3]); + break; + + case PI_CMD_I2CWQ: res = i2cWriteQuick(p[1], p[2]); break; + + case PI_CMD_I2CWS: res = i2cWriteByte(p[1], p[2]); break; + + case PI_CMD_I2CWW: + memcpy(&p[4], buf, 4); + res = i2cWriteWordData(p[1], p[2], p[4]); + break; + + + case PI_CMD_MICS: - DBG(0,"mics %d", p[1]); if (p[1] <= PI_MAX_MICS_DELAY) myGpioDelay(p[1]); else res = PI_BAD_MICS_DELAY; break; @@ -1153,15 +1326,17 @@ static int myDoCommand(uint32_t *p, gpioExtent_t *oExt) case PI_CMD_PRG: res = gpioGetPWMrange(p[1]); break; case PI_CMD_PROC: - res = gpioStoreScript((char *)p[2]); + res = gpioStoreScript(buf); break; case PI_CMD_PROCD: res = gpioDeleteScript(p[1]); break; - case PI_CMD_PROCP: res = gpioScriptStatus(p[1], oExt[0].ptr); break; + case PI_CMD_PROCP: + res = gpioScriptStatus(p[1], (uint32_t *)buf); + break; case PI_CMD_PROCR: - res = gpioRunScript(p[1], p[2], (uint32_t *)p[3]); + res = gpioRunScript(p[1], p[3]/4, (uint32_t *)buf); break; case PI_CMD_PROCS: res = gpioStopScript(p[1]); break; @@ -1208,19 +1383,70 @@ static int myDoCommand(uint32_t *p, gpioExtent_t *oExt) } break; - case PI_CMD_SLRO: res = gpioSerialReadOpen(p[1], p[2]); break; + + + case PI_CMD_SERRB: res = serReadByte(p[1]); break; + + case PI_CMD_SERWB: res = serWriteByte(p[1], p[2]); break; + + case PI_CMD_SERC: res = serClose(p[1]); break; + + case PI_CMD_SERDA: res = serDataAvailable(p[1]); break; + + case PI_CMD_SERO: res = serOpen(buf, p[1], p[2]); break; + + case PI_CMD_SERR: + if (p[2] > bufSize) p[2] = bufSize; + res = serRead(p[1], buf, p[2]); + break; + + case PI_CMD_SERW: res = serWrite(p[1], buf, p[3]); break; + + case PI_CMD_SLR: - if (p[2] < oExt[0].size) oExt[0].size = p[2]; - res = gpioSerialRead(p[1], oExt[0].ptr, oExt[0].size); + if (p[2] > bufSize) p[2] = bufSize; + res = gpioSerialRead(p[1], buf, p[2]); break; case PI_CMD_SLRC: res = gpioSerialReadClose(p[1]); break; + case PI_CMD_SLRO: res = gpioSerialReadOpen(p[1], p[2]); break; + + + + case PI_CMD_SPIC: res = spiClose(p[1]); break; + + case PI_CMD_SPIO: + memcpy(&p[4], buf, 4); + res = spiOpen(p[1], p[2], p[4]); + break; + + case PI_CMD_SPIR: + if (p[2] > bufSize) p[2] = bufSize; + res = spiRead(p[1], buf, p[2]); + break; + + case PI_CMD_SPIW: + if (p[3] > bufSize) p[3] = bufSize; + res = spiWrite(p[1], buf, p[3]); + break; + + case PI_CMD_SPIX: + if (p[3] > bufSize) p[3] = bufSize; + res = spiXfer(p[1], buf, buf, p[3]); + break; + + + case PI_CMD_TICK: res = gpioTick(); break; case PI_CMD_TRIG: - if (myPermit(p[1])) res = gpioTrigger(p[1], p[2], p[3]); + if (myPermit(p[1])) + { + memcpy(&p[4], buf, 4); + res = gpioTrigger(p[1], p[2], p[4]); + } else { DBG(DBG_USER, "gpioTrigger: gpio %d, no permission to update", p[1]); @@ -1239,15 +1465,18 @@ static int myDoCommand(uint32_t *p, gpioExtent_t *oExt) } break; + + case PI_CMD_WVAG: /* need to mask off any non permitted gpios */ mask = gpioMask; - pulse = (gpioPulse_t *)p[2]; + pulse = (gpioPulse_t *)buf; + j = p[3]/sizeof(gpioPulse_t); masked = 0; - for (i=0; i= 0)) res = PI_SOME_PERMITTED; @@ -1275,7 +1504,10 @@ static int myDoCommand(uint32_t *p, gpioExtent_t *oExt) case PI_CMD_WVAS: if (myPermit(p[1])) - res = gpioWaveAddSerial(p[1], p[2], p[3], p[4], (char *)p[5]); + { + memcpy(&p[4], buf, 4); + res = gpioWaveAddSerial(p[1], p[2], p[4], p[3]-4, buf+4); + } else { DBG( @@ -1337,8 +1569,12 @@ static int myDoCommand(uint32_t *p, gpioExtent_t *oExt) case PI_CMD_WVTXR: res = gpioWaveTxSend(p[1], PI_WAVE_MODE_REPEAT); break; + default: + res = PI_UNKNOWN_COMMAND; + break; } - return (res); + + return res; } /* ----------------------------------------------------------------------- */ @@ -1993,6 +2229,1001 @@ int rawWaveAddGeneric(unsigned numIn1, rawWave_t *in1) else return PI_TOO_MANY_PULSES; } +/* ======================================================================= */ + +int i2cWriteQuick(unsigned handle, unsigned bit) +{ + int err; + + DBG(DBG_USER, "handle=%d bit=%d", handle, bit); + + CHECK_INITED; + + if (handle >= PI_I2C_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (i2cInfo[handle].state == PI_I2C_CLOSED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (bit > 1) + SOFT_ERROR(PI_BAD_PARAM, "bad bit (%d)", bit); + + err = my_smbus_access(i2cInfo[handle].fd, bit, 0, PI_I2C_SMBUS_QUICK, NULL); + + if (err < 0) return PI_I2C_WRITE_FAILED; + + return err; +} + +int i2cReadByte(unsigned handle) +{ + union my_smbus_data data; + + DBG(DBG_USER, "handle=%d", handle); + + CHECK_INITED; + + if (handle >= PI_I2C_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (i2cInfo[handle].state == PI_I2C_CLOSED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (my_smbus_access( + i2cInfo[handle].fd, PI_I2C_SMBUS_READ, 0, PI_I2C_SMBUS_BYTE, &data)) + return PI_I2C_READ_FAILED; + else + return 0xFF & data.byte; +} + + +int i2cWriteByte(unsigned handle, unsigned bVal) +{ + int err; + + DBG(DBG_USER, "handle=%d bVal=%d", handle, bVal); + + CHECK_INITED; + + if (handle >= PI_I2C_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (i2cInfo[handle].state == PI_I2C_CLOSED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (bVal > 0xFF) + SOFT_ERROR(PI_BAD_PARAM, "bad bVal (%d)", bVal); + + err = my_smbus_access( + i2cInfo[handle].fd, + PI_I2C_SMBUS_WRITE, + bVal, + PI_I2C_SMBUS_BYTE, + NULL); + + if (err < 0) return PI_I2C_WRITE_FAILED; + + return err; +} + + +int i2cReadByteData(unsigned handle, unsigned reg) +{ + union my_smbus_data data; + + DBG(DBG_USER, "handle=%d reg=%d", handle, reg); + + CHECK_INITED; + + if (handle >= PI_I2C_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (i2cInfo[handle].state == PI_I2C_CLOSED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (reg > 0xFF) + SOFT_ERROR(PI_BAD_PARAM, "bad reg (%d)", reg); + + if (my_smbus_access( + i2cInfo[handle].fd, PI_I2C_SMBUS_READ, reg, PI_I2C_SMBUS_BYTE_DATA, &data)) + return PI_I2C_READ_FAILED; + else + return 0xFF & data.byte; +} + + +int i2cWriteByteData(unsigned handle, unsigned reg, unsigned bVal) +{ + union my_smbus_data data; + + int err; + + DBG(DBG_USER, "handle=%d reg=%d bVal=%d", handle, reg, bVal); + + CHECK_INITED; + + if (handle >= PI_I2C_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (i2cInfo[handle].state == PI_I2C_CLOSED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (reg > 0xFF) + SOFT_ERROR(PI_BAD_PARAM, "bad reg (%d)", reg); + + if (bVal > 0xFF) + SOFT_ERROR(PI_BAD_PARAM, "bad bVal (%d)", bVal); + + data.byte = bVal; + + err = my_smbus_access( + i2cInfo[handle].fd, + PI_I2C_SMBUS_WRITE, + reg, + PI_I2C_SMBUS_BYTE_DATA, + &data); + + if (err < 0) return PI_I2C_WRITE_FAILED; + + return err; +} + + +int i2cReadWordData(unsigned handle, unsigned reg) +{ + union my_smbus_data data; + + DBG(DBG_USER, "handle=%d reg=%d", handle, reg); + + CHECK_INITED; + + if (handle >= PI_I2C_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (i2cInfo[handle].state == PI_I2C_CLOSED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (reg > 0xFF) + SOFT_ERROR(PI_BAD_PARAM, "bad reg (%d)", reg); + + if (my_smbus_access( + i2cInfo[handle].fd, PI_I2C_SMBUS_READ, reg, PI_I2C_SMBUS_WORD_DATA, &data)) + return PI_I2C_READ_FAILED; + else + return 0xFFFF & data.word; +} + + +int i2cWriteWordData(unsigned handle, unsigned reg, unsigned wVal) +{ + union my_smbus_data data; + + int err; + + DBG(DBG_USER, "handle=%d reg=%d wVal=%d", handle, reg, wVal); + + CHECK_INITED; + + if (handle >= PI_I2C_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (i2cInfo[handle].state == PI_I2C_CLOSED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (reg > 0xFF) + SOFT_ERROR(PI_BAD_PARAM, "bad reg (%d)", reg); + + if (wVal > 0xFFFF) + SOFT_ERROR(PI_BAD_PARAM, "bad wVal (%d)", wVal); + + data.word = wVal; + + err = my_smbus_access( + i2cInfo[handle].fd, + PI_I2C_SMBUS_WRITE, + reg, + PI_I2C_SMBUS_WORD_DATA, + &data); + + if (err < 0) return PI_I2C_WRITE_FAILED; + + return err; +} + + +int i2cProcessCall(unsigned handle, unsigned reg, unsigned wVal) +{ + union my_smbus_data data; + + DBG(DBG_USER, "handle=%d reg=%d wVal=%d", handle, reg, wVal); + + CHECK_INITED; + + if (handle >= PI_I2C_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (i2cInfo[handle].state == PI_I2C_CLOSED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (reg > 0xFF) + SOFT_ERROR(PI_BAD_PARAM, "bad reg (%d)", reg); + + if (wVal > 0xFFFF) + SOFT_ERROR(PI_BAD_PARAM, "bad wVal (%d)", wVal); + + data.word = wVal; + + if (my_smbus_access( + i2cInfo[handle].fd, PI_I2C_SMBUS_WRITE, reg, PI_I2C_SMBUS_PROC_CALL, &data)) + return PI_I2C_READ_FAILED; + else + return 0xFFFF & data.word; +} + + +int i2cReadBlockData(unsigned handle, unsigned reg, char *buf) +{ + union my_smbus_data data; + + int i; + + DBG(DBG_USER, "handle=%d reg=%d buf=%08X", handle, reg, (unsigned)buf); + + CHECK_INITED; + + if (handle >= PI_I2C_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (i2cInfo[handle].state == PI_I2C_CLOSED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (reg > 0xFF) + SOFT_ERROR(PI_BAD_PARAM, "bad reg (%d)", reg); + + if (my_smbus_access( + i2cInfo[handle].fd, PI_I2C_SMBUS_READ, reg, PI_I2C_SMBUS_BLOCK_DATA, &data)) + return PI_I2C_READ_FAILED; + else + { + for (i=1; i<=data.block[0]; i++) buf[i-1] = data.block[i]; + return data.block[0]; + } +} + + +int i2cWriteBlockData( + unsigned handle, unsigned reg, char *buf, unsigned count) +{ + union my_smbus_data data; + + int i, err; + + DBG(DBG_USER, "handle=%d reg=%d count=%d [%s]", + handle, reg, count, myBuf2Str(count, buf)); + + CHECK_INITED; + + if (handle >= PI_I2C_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (i2cInfo[handle].state == PI_I2C_CLOSED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (reg > 0xFF) + SOFT_ERROR(PI_BAD_PARAM, "bad reg (%d)", reg); + + if ((count < 1) || (count > 32)) + SOFT_ERROR(PI_BAD_PARAM, "bad count (%d)", count); + + for (i=1; i<=count; i++) data.block[i] = buf[i-1]; + data.block[0] = count; + + err = my_smbus_access( + i2cInfo[handle].fd, + PI_I2C_SMBUS_WRITE, + reg, + PI_I2C_SMBUS_BLOCK_DATA, + &data); + + if (err < 0) return PI_I2C_WRITE_FAILED; + + return err; +} + + +int i2cBlockProcessCall( + unsigned handle, unsigned reg, char *buf, unsigned count) +{ + union my_smbus_data data; + + int i; + + DBG(DBG_USER, "handle=%d reg=%d count=%d [%s]", + handle, reg, count, myBuf2Str(count, buf)); + + CHECK_INITED; + + if (handle >= PI_I2C_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (i2cInfo[handle].state == PI_I2C_CLOSED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (reg > 0xFF) + SOFT_ERROR(PI_BAD_PARAM, "bad reg (%d)", reg); + + if ((count < 1) || (count > 32)) + SOFT_ERROR(PI_BAD_PARAM, "bad count (%d)", count); + + for (i=1; i<=count; i++) data.block[i] = buf[i-1]; + data.block[0] = count; + if (my_smbus_access( + i2cInfo[handle].fd, PI_I2C_SMBUS_WRITE, reg, PI_I2C_SMBUS_BLOCK_PROC_CALL, &data)) + return PI_I2C_READ_FAILED; + else + { + for (i=1; i<=data.block[0]; i++) buf[i-1] = data.block[i]; + return data.block[0]; + } +} + + +int i2cReadI2CBlockData( + unsigned handle, unsigned reg, char *buf, unsigned count) +{ + union my_smbus_data data; + + int i; + uint32_t size; + + DBG(DBG_USER, "handle=%d reg=%d count=%d buf=%08X", + handle, reg, count, (unsigned)buf); + + CHECK_INITED; + + if (handle >= PI_I2C_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (i2cInfo[handle].state == PI_I2C_CLOSED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (reg > 0xFF) + SOFT_ERROR(PI_BAD_PARAM, "bad reg (%d)", reg); + + if ((count < 1) || (count > 32)) + SOFT_ERROR(PI_BAD_PARAM, "bad count (%d)", count); + + if (count == 32) + size = PI_I2C_SMBUS_I2C_BLOCK_BROKEN; + else + size = PI_I2C_SMBUS_I2C_BLOCK_DATA; + + data.block[0] = count; + if (my_smbus_access( + i2cInfo[handle].fd, PI_I2C_SMBUS_READ, reg, size, &data)) + return PI_I2C_READ_FAILED; + else + { + for (i = 1; i <= data.block[0]; i++) buf[i-1] = data.block[i]; + return data.block[0]; + } +} + + +int i2cWriteI2CBlockData( + unsigned handle, unsigned reg, char *buf, unsigned count) +{ + union my_smbus_data data; + + int i, err; + + DBG(DBG_USER, "handle=%d reg=%d count=%d [%s]", + handle, reg, count, myBuf2Str(count, buf)); + + CHECK_INITED; + + if (handle >= PI_I2C_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (i2cInfo[handle].state == PI_I2C_CLOSED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (reg > 0xFF) + SOFT_ERROR(PI_BAD_PARAM, "bad reg (%d)", reg); + + if ((count < 1) || (count > 32)) + SOFT_ERROR(PI_BAD_PARAM, "bad count (%d)", count); + + for (i=1; i<=count; i++) data.block[i] = buf[i-1]; + + data.block[0] = count; + + err = my_smbus_access( + i2cInfo[handle].fd, + PI_I2C_SMBUS_WRITE, + reg, + PI_I2C_SMBUS_I2C_BLOCK_BROKEN, + &data); + + if (err < 0) return PI_I2C_WRITE_FAILED; + + return err; +} + +int i2cWriteDevice(unsigned handle, char *buf, unsigned count) +{ + int bytes; + + DBG(DBG_USER, "handle=%d count=%d [%s]", + handle, count, myBuf2Str(count, buf)); + + CHECK_INITED; + + if (handle >= PI_I2C_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (i2cInfo[handle].state == PI_I2C_CLOSED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if ((count < 1) || (count > PI_MAX_I2C_DEVICE_COUNT)) + SOFT_ERROR(PI_BAD_PARAM, "bad count (%d)", count); + + bytes = write(i2cInfo[handle].fd, buf, count); + + if (bytes != count) + return PI_I2C_WRITE_FAILED; + else + return 0; +} + +int i2cReadDevice(unsigned handle, char *buf, unsigned count) +{ + int bytes; + + DBG(DBG_USER, "handle=%d count=%d buf=%08X", + handle, count, (unsigned)buf); + + CHECK_INITED; + + if (handle >= PI_I2C_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (i2cInfo[handle].state == PI_I2C_CLOSED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if ((count < 1) || (count > PI_MAX_I2C_DEVICE_COUNT)) + SOFT_ERROR(PI_BAD_PARAM, "bad count (%d)", count); + + bytes = read(i2cInfo[handle].fd, buf, count); + + if (bytes != count) + return PI_I2C_READ_FAILED; + else + return bytes; +} + +int i2cOpen(unsigned i2cBus, unsigned i2cAddr, unsigned i2cFlags) +{ + char dev[32]; + int i, slot, fd; + + DBG(DBG_USER, "i2cBus=%d i2cAddr=%d flags=0x%X", + i2cBus, i2cAddr, i2cFlags); + + CHECK_INITED; + + if (i2cBus >= PI_NUM_I2C_BUS) + SOFT_ERROR(PI_BAD_I2C_BUS, "bad I2C bus (%d)", i2cBus); + + if ((i2cAddr < 0x08) || (i2cAddr > 0x77)) + SOFT_ERROR(PI_BAD_I2C_ADDR, "bad I2C address (0x%X)", i2cAddr); + + if (i2cFlags) + SOFT_ERROR(PI_BAD_FLAGS, "bad flags (0x%X)", i2cFlags); + + slot = -1; + + for (i=0; i= PI_I2C_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (i2cInfo[handle].state != PI_I2C_OPENED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (i2cInfo[handle].fd >= 0) close(i2cInfo[handle].fd); + + i2cInfo[handle].fd = -1; + i2cInfo[handle].state = PI_I2C_CLOSED; + + return 0; +} + +/* ======================================================================= */ + + +int spiOpen(unsigned spiChan, unsigned spiBaud, unsigned spiFlags) +{ + int i, slot, fd; + char spiMode; + char spiBits = 8; + char dev[32]; + + DBG(DBG_USER, "spiChan=%d spiBaud=%d spiFlags=0x%X", + spiChan, spiBaud, spiFlags); + + CHECK_INITED; + + spiMode = spiFlags & 3; + spiBits = 8; + + if (spiChan >= PI_NUM_SPI_CHANNEL) + SOFT_ERROR(PI_BAD_SPI_CHANNEL, "bad spiChan (%d)", spiChan); + + if (!spiBaud) + SOFT_ERROR(PI_BAD_SPI_SPEED, "bad spiBaud (%d)", spiBaud); + + if (spiFlags > 3) + SOFT_ERROR(PI_BAD_FLAGS, "bad spiFlags (0x%X)", spiFlags); + + slot = -1; + + for (i=0; i= PI_SPI_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (spiInfo[handle].state != PI_SPI_OPENED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (spiInfo[handle].fd >= 0) close(spiInfo[handle].fd); + + spiInfo[handle].fd = -1; + spiInfo[handle].state = PI_I2C_CLOSED; + + return 0; +} + +int spiRead(unsigned handle, char *buf, unsigned count) +{ + int err; + + struct spi_ioc_transfer spi; + + DBG(DBG_USER, "handle=%d count=%d [%s]", + handle, count, myBuf2Str(count, buf)); + + CHECK_INITED; + + if (handle >= PI_SPI_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (spiInfo[handle].state != PI_SPI_OPENED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if ((count < 1) || (count > PI_MAX_SPI_DEVICE_COUNT)) + SOFT_ERROR(PI_BAD_SPI_COUNT, "bad count (%d)", count); + + spi.tx_buf = (unsigned) NULL; + spi.rx_buf = (unsigned) buf; + spi.len = count; + spi.speed_hz = spiInfo[handle].speed; + spi.delay_usecs = 0; + spi.bits_per_word = 8; + spi.cs_change = 0; + + err = ioctl(spiInfo[handle].fd, SPI_IOC_MESSAGE(1), &spi); + + if (err < 0) return PI_SPI_XFER_FAILED; + else return err; +} + +int spiWrite(unsigned handle, char *buf, unsigned count) +{ + int err; + struct spi_ioc_transfer spi; + + DBG(DBG_USER, "handle=%d count=%d [%s]", + handle, count, myBuf2Str(count, buf)); + + CHECK_INITED; + + if (handle >= PI_SPI_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (spiInfo[handle].state != PI_SPI_OPENED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if ((count < 1) || (count > PI_MAX_SPI_DEVICE_COUNT)) + SOFT_ERROR(PI_BAD_SPI_COUNT, "bad count (%d)", count); + + spi.tx_buf = (unsigned) buf; + spi.rx_buf = (unsigned) NULL; + spi.len = count; + spi.speed_hz = spiInfo[handle].speed; + spi.delay_usecs = 0; + spi.bits_per_word = 8; + spi.cs_change = 0; + + err = ioctl(spiInfo[handle].fd, SPI_IOC_MESSAGE(1), &spi); + + if (err < 0) return PI_SPI_XFER_FAILED; + else return err; +} + +int spiXfer(unsigned handle, char *txBuf, char *rxBuf, unsigned count) +{ + int err; + struct spi_ioc_transfer spi; + + DBG(DBG_USER, "handle=%d count=%d [%s]", + handle, count, myBuf2Str(count, txBuf)); + + CHECK_INITED; + + if (handle >= PI_SPI_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (spiInfo[handle].state != PI_SPI_OPENED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if ((count < 1) || (count > PI_MAX_SPI_DEVICE_COUNT)) + SOFT_ERROR(PI_BAD_SPI_COUNT, "bad count (%d)", count); + + spi.tx_buf = (unsigned long)txBuf; + spi.rx_buf = (unsigned long)rxBuf; + spi.len = count; + spi.speed_hz = spiInfo[handle].speed; + spi.delay_usecs = 0; + spi.bits_per_word = 8; + spi.cs_change = 0; + + err = ioctl(spiInfo[handle].fd, SPI_IOC_MESSAGE(1), &spi); + + if (err < 0) return PI_SPI_XFER_FAILED; + else return err; +} + +/* ======================================================================= */ + + +int serOpen(char *tty, unsigned serBaud, unsigned serFlags) +{ + struct termios new; + int speed; + int fd; + int i, slot; + + DBG(DBG_USER, "tty=%s serBaud=%d serFlags=0x%X", tty, serBaud, serFlags); + + CHECK_INITED; + + if (strncmp("/dev/tty", tty, 8)) + SOFT_ERROR(PI_BAD_SER_DEVICE, "bad device (%s)", tty); + + switch (serBaud) + { + case 50: speed = B50; break; + case 75: speed = B75; break; + case 110: speed = B110; break; + case 134: speed = B134; break; + case 150: speed = B150; break; + case 200: speed = B200; break; + case 300: speed = B300; break; + case 600: speed = B600; break; + case 1200: speed = B1200; break; + case 1800: speed = B1800; break; + case 2400: speed = B2400; break; + case 4800: speed = B4800; break; + case 9600: speed = B9600; break; + case 19200: speed = B19200; break; + case 38400: speed = B38400; break; + case 57600: speed = B57600; break; + case 115200: speed = B115200; break; + case 230400: speed = B230400; break; + + default: + SOFT_ERROR(PI_BAD_SER_SPEED, "bad speed (%d)", serBaud); + } + + if (serFlags) + SOFT_ERROR(PI_BAD_FLAGS, "bad flags (0x%X)", serFlags); + + slot = -1; + + for (i=0; i= PI_SER_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (serInfo[handle].state != PI_SER_OPENED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (serInfo[handle].fd >= 0) close(serInfo[handle].fd); + + serInfo[handle].fd = -1; + serInfo[handle].state = PI_SER_CLOSED; + + return 0; +} + +int serWriteByte(unsigned handle, unsigned bVal) +{ + char c; + + DBG(DBG_USER, "handle=%d bVal=%d", handle, bVal); + + CHECK_INITED; + + if (handle >= PI_SER_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (serInfo[handle].state != PI_SER_OPENED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (bVal > 0xFF) + SOFT_ERROR(PI_BAD_PARAM, "bad parameter (%d)", bVal); + + c = bVal; + + if (write(serInfo[handle].fd, &c, 1) != 1) + return PI_SER_WRITE_FAILED; + else + return 0; +} + +int serReadByte(unsigned handle) +{ + char x; + + DBG(DBG_USER, "handle=%d", handle); + + CHECK_INITED; + + if (handle >= PI_SER_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (serInfo[handle].state != PI_SER_OPENED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (read(serInfo[handle].fd, &x, 1) != 1) + { + if (errno == EAGAIN) + return PI_SER_READ_NO_DATA; + else + return PI_SER_READ_FAILED; + } + + return ((int)x) & 0xFF; +} + +int serWrite(unsigned handle, char *buf, unsigned count) +{ + DBG(DBG_USER, "handle=%d count=%d [%s]", + handle, count, myBuf2Str(count, buf)); + + CHECK_INITED; + + if (handle >= PI_SER_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (serInfo[handle].state != PI_SER_OPENED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (!count) + SOFT_ERROR(PI_BAD_PARAM, "bad count (%d)", count); + + if (write(serInfo[handle].fd, buf, count) != count) + return PI_SER_WRITE_FAILED; + else + return 0; +} + +int serRead(unsigned handle, char *buf, unsigned count) +{ + int r; + + DBG(DBG_USER, "handle=%d count=%d buf=0x%X", handle, count, (unsigned)buf); + + CHECK_INITED; + + if (handle >= PI_SER_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (serInfo[handle].state != PI_SER_OPENED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (!count) + SOFT_ERROR(PI_BAD_PARAM, "bad count (%d)", count); + + r = read(serInfo[handle].fd, buf, count); + + if (r == -1) + { + if (errno == EAGAIN) + return PI_SER_READ_NO_DATA; + else + return PI_SER_READ_FAILED; + } + else + { + buf[r] = 0; + return r; + } +} + +int serDataAvailable(unsigned handle) +{ + int result; + + DBG(DBG_USER, "handle=%d", handle); + + CHECK_INITED; + + if (handle >= PI_SER_SLOTS) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (serInfo[handle].state != PI_SER_OPENED) + SOFT_ERROR(PI_BAD_HANDLE, "bad handle (%d)", handle); + + if (ioctl(serInfo[handle].fd, FIONREAD, &result) == -1) return 0; + + return result; +} /* ======================================================================= */ @@ -2300,7 +3531,7 @@ static void dmaInitCbs(void) p->next = dmaCbAdr(0) | DMA_BUS_ADR; - DBG(DBG_STARTUP, "DMA page type size = %d", sizeof(dmaIPage_t)); + DBG(DBG_STARTUP, "DMA page type count = %d", sizeof(dmaIPage_t)); DBG(DBG_STARTUP, "%d control blocks (exp=%d)", b+1, NUM_CBS); } @@ -2880,13 +4111,12 @@ static int scrSys(char *cmd, int param) static void *pthScript(void *x) { gpioScript_t *s; - gpioExtent_t oExt[3]; - char buf[CMD_BUF_SIZE]; cmdInstr_t instr; int p1, p2, p1o, p2o, *t1, *t2; - int PC, A, F, SP; int S[PI_SCRIPT_STACK_SIZE]; + char buf[CMD_MAX_EXTENSION]; + S[0] = 0; /* to prevent compiler warning */ @@ -2915,18 +4145,20 @@ static void *pthScript(void *x) p1o = instr.p[1]; p2o = instr.p[2]; - if (instr.opt[0] == CMD_VAR) instr.p[1] = s->script.var[p1o]; - else if (instr.opt[0] == CMD_PAR) instr.p[1] = s->script.par[p1o]; + if (instr.opt[1] == CMD_VAR) instr.p[1] = s->script.var[p1o]; + else if (instr.opt[1] == CMD_PAR) instr.p[1] = s->script.par[p1o]; - if (instr.opt[1] == CMD_VAR) instr.p[2] = s->script.var[p2o]; - else if (instr.opt[1] == CMD_PAR) instr.p[2] = s->script.par[p2o]; + if (instr.opt[2] == CMD_VAR) instr.p[2] = s->script.var[p2o]; + else if (instr.opt[2] == CMD_PAR) instr.p[2] = s->script.par[p2o]; if (instr.p[0] < 100) { - oExt[0].ptr = buf; - oExt[0].size = CMD_BUF_SIZE-1; + if (instr.p[3]) + { + memcpy(buf, (char *)instr.p[4], instr.p[3]); + } - A = myDoCommand(instr.p, oExt); + A = myDoCommand(instr.p, sizeof(buf)-1, buf); F = A; @@ -2948,7 +4180,7 @@ static void *pthScript(void *x) case PI_CMD_CMP: F=A-p1; PC++; break; case PI_CMD_DCR: - if (instr.opt[0] == CMD_PAR) + if (instr.opt[1] == CMD_PAR) {--s->script.par[p1o]; F=s->script.par[p1o];} else {--s->script.var[p1o]; F=s->script.var[p1o];} @@ -2962,7 +4194,7 @@ static void *pthScript(void *x) case PI_CMD_HALT: s->run_state = PI_SCRIPT_HALTED; break; case PI_CMD_INR: - if (instr.opt[0] == CMD_PAR) + if (instr.opt[1] == CMD_PAR) {++s->script.par[p1o]; F=s->script.par[p1o];} else {++s->script.var[p1o]; F=s->script.var[p1o];} @@ -2982,13 +4214,18 @@ static void *pthScript(void *x) case PI_CMD_JZ: if (!F) PC=p1; else PC++; break; case PI_CMD_LD: - if (instr.opt[0] == CMD_PAR) s->script.par[p1o]=p2; + if (instr.opt[1] == CMD_PAR) s->script.par[p1o]=p2; else s->script.var[p1o]=p2; PC++; break; case PI_CMD_LDA: A=p1; PC++; break; + case PI_CMD_LDAB: + if ((p1 >= 0) && (p1 < sizeof(buf))) A = buf[p1]; + PC++; + break; + case PI_CMD_MLT: A*=p1; F=A; PC++; break; case PI_CMD_MOD: A%=p1; F=A; PC++; break; @@ -2996,7 +4233,7 @@ static void *pthScript(void *x) case PI_CMD_OR: A|=p1; F=A; PC++; break; case PI_CMD_POP: - if (instr.opt[0] == CMD_PAR) + if (instr.opt[1] == CMD_PAR) s->script.par[p1o]=scrPop(s, &SP, S); else s->script.var[p1o]=scrPop(s, &SP, S); @@ -3006,7 +4243,7 @@ static void *pthScript(void *x) case PI_CMD_POPA: A=scrPop(s, &SP, S); PC++; break; case PI_CMD_PUSH: - if (instr.opt[0] == CMD_PAR) + if (instr.opt[1] == CMD_PAR) scrPush(s, &SP, S, s->script.par[p1o]); else scrPush(s, &SP, S, s->script.var[p1o]); @@ -3018,7 +4255,7 @@ static void *pthScript(void *x) case PI_CMD_RET: PC=scrPop(s, &SP, S); break; case PI_CMD_RL: - if (instr.opt[0] == CMD_PAR) + if (instr.opt[1] == CMD_PAR) {s->script.par[p1o]<<=p2; F=s->script.par[p1o];} else {s->script.var[p1o]<<=p2; F=s->script.var[p1o];} @@ -3028,7 +4265,7 @@ static void *pthScript(void *x) case PI_CMD_RLA: A<<=p1; F=A; PC++; break; case PI_CMD_RR: - if (instr.opt[0] == CMD_PAR) + if (instr.opt[1] == CMD_PAR) {s->script.par[p1o]>>=p2; F=s->script.par[p1o];} else {s->script.var[p1o]>>=p2; F=s->script.var[p1o];} @@ -3038,18 +4275,31 @@ static void *pthScript(void *x) case PI_CMD_RRA: A>>=p1; F=A; PC++; break; case PI_CMD_STA: - if (instr.opt[0] == CMD_PAR) s->script.par[p1o]=A; + if (instr.opt[1] == CMD_PAR) s->script.par[p1o]=A; else s->script.var[p1o]=A; PC++; break; + case PI_CMD_STAB: + if ((p1 >= 0) && (p1 < sizeof(buf))) buf[p1] = A; + PC++; + break; + case PI_CMD_SUB: A-=p1; F=A; PC++; break; + case PI_CMD_SYS: + A=scrSys((char*)instr.p[4], A); + F=A; + PC++; + break; + + case PI_CMD_WAIT: A=scrWait(s, p1); F=A; PC++; break; + case PI_CMD_X: - if (instr.opt[0] == CMD_PAR) t1 = &s->script.par[p1o]; + if (instr.opt[1] == CMD_PAR) t1 = &s->script.par[p1o]; else t1 = &s->script.var[p1o]; - if (instr.opt[1] == CMD_PAR) t2 = &s->script.par[p2o]; + if (instr.opt[2] == CMD_PAR) t2 = &s->script.par[p2o]; else t2 = &s->script.var[p2o]; scrSwap(t1, t2); @@ -3057,17 +4307,13 @@ static void *pthScript(void *x) break; case PI_CMD_XA: - if (instr.opt[0] == CMD_PAR) + if (instr.opt[1] == CMD_PAR) scrSwap(&s->script.par[p1o], &A); else scrSwap(&s->script.var[p1o], &A); PC++; break; - case PI_CMD_SYS: A=scrSys((char*)p1, A); F=A; PC++; break; - - case PI_CMD_WAIT: A=scrWait(s, p1); F=A; PC++; break; - case PI_CMD_XOR: A^=p1; F=A; PC++; break; } @@ -3141,14 +4387,12 @@ static void * pthTimerTick(void *x) static void * pthFifoThread(void *x) { - char buf[CMD_BUF_SIZE]; + char buf[CMD_MAX_EXTENSION]; int idx, flags, len, res, i; - uint32_t p[10]; - void *v[10]; - gpioExtent_t oExt[3]; + uint32_t p[CMD_P_ARR]; cmdCtlParse_t ctl; - char *pp; uint32_t *param; + char v[CMD_MAX_EXTENSION]; myCreatePipe(PI_INPFIFO, 0662); @@ -3183,20 +4427,13 @@ static void * pthFifoThread(void *x) while (((ctl.eaten)= 0)) { - if ((idx=cmdParse(buf, p, v, &ctl)) >= 0) + if ((idx=cmdParse(buf, p, CMD_MAX_EXTENSION, v, &ctl)) >= 0) { - oExt[0].ptr = buf; - oExt[0].size = CMD_BUF_SIZE-1; + /* make sure extensions are null terminated */ - switch (p[0]) - { - case PI_CMD_PROC: p[2] = (uint32_t)v[1]; break; - case PI_CMD_PROCR: p[3] = (uint32_t)v[1]; break; - case PI_CMD_WVAG: p[2] = (uint32_t)v[1]; break; - case PI_CMD_WVAS: p[5] = (uint32_t)v[1]; break; - } + v[p[3]] = 0; - res = myDoCommand(p, oExt); + res = myDoCommand(p, sizeof(v)-1, v); switch (cmdInfo[idx].rv) { @@ -3228,9 +4465,7 @@ static void * pthFifoThread(void *x) if (res < 0) fprintf(outFifo, "%d\n", res); else if (res > 0) { - pp = oExt[0].ptr; - pp[res] = 0; - fprintf(outFifo, "%s", (char *)oExt[0].ptr); + fwrite(v, 1, res, outFifo); } break; @@ -3239,7 +4474,7 @@ static void * pthFifoThread(void *x) else { fprintf(outFifo, "%d", res); - param = oExt[0].ptr; + param = (uint32_t *)v; for (i=0; i 0) + case PI_CMD_I2CPK: + case PI_CMD_I2CRD: + case PI_CMD_I2CRI: + case PI_CMD_I2CRK: + case PI_CMD_SERR: + case PI_CMD_SLR: + case PI_CMD_SPIX: + case PI_CMD_SPIR: + + if (p[3] > 0) { - write(sock, oExt[0].ptr, res); + write(sock, buf, p[3]); } break; - case PI_CMD_PROCP: /* extension */ + case PI_CMD_PROCP: - if (res >= 0) + if (p[3] >= 0) { - write(sock, oExt[0].ptr, sizeof(uint32_t)*PI_MAX_SCRIPT_PARAMS); + write(sock, buf, sizeof(uint32_t)*PI_MAX_SCRIPT_PARAMS); } break; @@ -3943,7 +5056,7 @@ static void initPCM(unsigned bits) /* enable PCM */ - pcmReg[PCM_CS] |= PCM_CS_EN ; + pcmReg[PCM_CS] |= PCM_CS_EN; /* enable tx */ @@ -4291,7 +5404,7 @@ static void initReleaseResources(void) /* ======================================================================= */ -int getBitInBytes(int bitPos, uint8_t *buf, int numBits) +int getBitInBytes(int bitPos, char *buf, int numBits) { int bitp, bufp; @@ -4307,14 +5420,14 @@ int getBitInBytes(int bitPos, uint8_t *buf, int numBits) /* ----------------------------------------------------------------------- */ -void putBitInBytes(int bitPos, uint8_t *buf, int val) +void putBitInBytes(int bitPos, char *buf, int bit) { int bitp, bufp; bufp = bitPos / 8; bitp = 7 - (bitPos % 8); - if (val) buf[bufp] |= (1<= PI_MAX_SCRIPTS) return; + + if (gpioScript[script_id].state == PI_SCRIPT_IN_USE) { - fprintf(stderr, "p%d=%d ", i, gpioScript[s].script.par[i]); - } - fprintf(stderr, "\n"); + for (i=0; i PI_WAVE_MAX_PULSES) SOFT_ERROR(PI_TOO_MANY_PULSES, "bad number of pulses (%d)", numPulses); + if (!pulses) SOFT_ERROR(PI_BAD_POINTER, "bad (NULL) pulses pointer"); + for (p=0; p PI_MAX_USER_GPIO) SOFT_ERROR(PI_BAD_USER_GPIO, "bad gpio (%d)", gpio); - if ((baud < PI_WAVE_MIN_BAUD) || (baud > PI_WAVE_MAX_BAUD)) + if ((bbBaud < PI_WAVE_MIN_BAUD) || (bbBaud > PI_WAVE_MAX_BAUD)) SOFT_ERROR(PI_BAD_WAVE_BAUD, - "gpio %d, bad baud rate (%d)", gpio, baud); + "gpio %d, bad baud rate (%d)", gpio, bbBaud); if (numChar > PI_WAVE_MAX_CHARS) SOFT_ERROR(PI_TOO_MANY_CHARS, "too many chars (%d)", numChar); @@ -5097,7 +6221,7 @@ int gpioWaveAddSerial(unsigned gpio, if (!numChar) return 0; - waveBitDelay(baud, bitDelay); + waveBitDelay(bbBaud, bitDelay); p = 0; @@ -5180,26 +6304,26 @@ int gpioWaveAddSerial(unsigned gpio, int rawWaveAddSPI( rawSPI_t *spi, unsigned offset, - unsigned ss, - uint8_t *tx_bits, - unsigned num_tx_bits, - unsigned rx_bit_first, - unsigned rx_bit_last, - unsigned bits) + unsigned spiSS, + char *buf, + unsigned spiTxBits, + unsigned spiBitFirst, + unsigned spiBitLast, + unsigned spiBits) { int p, dbv, bit, halfbit; int rising_edge[2], read_cycle[2]; uint32_t on_bits, off_bits; int tx_bit_pos; - DBG(DBG_USER, "spi=%08X off=%d ss=%d tx=%08X, num=%d fb=%d lb=%d bits=%d", - (uint32_t)spi, offset, ss, (uint32_t)tx_bits, num_tx_bits, - rx_bit_first, rx_bit_last, bits); + DBG(DBG_USER, "spi=%08X off=%d spiSS=%d tx=%08X, num=%d fb=%d lb=%d spiBits=%d", + (uint32_t)spi, offset, spiSS, (uint32_t)buf, spiTxBits, + spiBitFirst, spiBitLast, spiBits); CHECK_INITED; - if (ss > PI_MAX_USER_GPIO) - SOFT_ERROR(PI_BAD_USER_GPIO, "bad gpio (%d)", ss); + if (spiSS > PI_MAX_USER_GPIO) + SOFT_ERROR(PI_BAD_USER_GPIO, "bad gpio (%d)", spiSS); /* CPOL CPHA @@ -5233,7 +6357,7 @@ int rawWaveAddSPI( tx_bit_pos = 0; - if (getBitInBytes(tx_bit_pos, tx_bits, num_tx_bits)) + if (getBitInBytes(tx_bit_pos, buf, spiTxBits)) { dbv = 1; on_bits |= (1<<(spi->mosi)); @@ -5244,8 +6368,8 @@ int rawWaveAddSPI( off_bits |= (1<<(spi->mosi)); } - if (spi->ss_pol) off_bits |= (1<ss_pol) off_bits |= (1<=rx_bit_first) && (bit<=rx_bit_last)) + if ((bit>=spiBitFirst) && (bit<=spiBitLast)) wf[2][p].flags = WAVE_FLAG_READ; - -; } else { - if (getBitInBytes(tx_bit_pos, tx_bits, num_tx_bits)) + if (getBitInBytes(tx_bit_pos, buf, spiTxBits)) { if (!dbv) on_bits |= (1<<(spi->mosi)); dbv = 1; @@ -5302,8 +6424,8 @@ int rawWaveAddSPI( on_bits = 0; off_bits = 0; - if (spi->ss_pol) on_bits |= (1<ss_pol) on_bits |= (1< PI_MAX_USER_GPIO) SOFT_ERROR(PI_BAD_USER_GPIO, "bad gpio (%d)", gpio); - if ((baud < PI_WAVE_MIN_BAUD) || (baud > PI_WAVE_MAX_BAUD)) + if ((bbBaud < PI_WAVE_MIN_BAUD) || (bbBaud > PI_WAVE_MAX_BAUD)) SOFT_ERROR(PI_BAD_WAVE_BAUD, - "gpio %d, bad baud rate (%d)", gpio, baud); + "gpio %d, bad baud rate (%d)", gpio, bbBaud); if (wfRx[gpio].mode != PI_WFRX_NONE) SOFT_ERROR(PI_GPIO_IN_USE, "gpio %d is already being used", gpio); - bitTime = MILLION / baud; + bitTime = MILLION / bbBaud; timeout = (10 * bitTime)/1000; if (timeout < 1) timeout = 1; @@ -5613,7 +6735,7 @@ int gpioSerialReadOpen(unsigned gpio, unsigned baud) wfRx[gpio].buf = malloc(SRX_BUF_SIZE); wfRx[gpio].bufSize = SRX_BUF_SIZE; wfRx[gpio].mode = PI_WFRX_SERIAL; - wfRx[gpio].baud = baud; + wfRx[gpio].baud = bbBaud; wfRx[gpio].timeout = timeout; wfRx[gpio].fullBit = bitTime; wfRx[gpio].halfBit = bitTime/2; @@ -5752,7 +6874,7 @@ int gpioSetAlertFunc(unsigned gpio, gpioAlertFunc_t f) /* ----------------------------------------------------------------------- */ -int gpioSetAlertFuncEx(unsigned gpio, gpioAlertFuncEx_t f, void * userdata) +int gpioSetAlertFuncEx(unsigned gpio, gpioAlertFuncEx_t f, void *userdata) { DBG(DBG_USER, "gpio=%d function=%08X userdata=%08X", gpio, (uint32_t)f, (uint32_t)userdata); @@ -5979,7 +7101,7 @@ int gpioTrigger(unsigned gpio, unsigned pulseLen, unsigned level) if (level > PI_ON) SOFT_ERROR(PI_BAD_LEVEL, "gpio %d, bad level (%d)", gpio, level); - if (pulseLen > PI_MAX_PULSELEN) + if ((pulseLen > PI_MAX_PULSELEN) || (!pulseLen)) SOFT_ERROR(PI_BAD_PULSELEN, "gpio %d, bad pulseLen (%d)", gpio, pulseLen); @@ -6063,13 +7185,13 @@ int gpioSetGetSamplesFuncEx(gpioGetSamplesFuncEx_t f, /* ----------------------------------------------------------------------- */ static int intGpioSetTimerFunc(unsigned id, - unsigned ms, - void * f, + unsigned millis, + void *f, int user, - void * userdata) + void *userdata) { - DBG(DBG_INTERNAL, "id=%d ms=%d function=%08X user=%d userdata=%08X", - id, ms, (uint32_t)f, user, (uint32_t)userdata); + DBG(DBG_INTERNAL, "id=%d millis=%d function=%08X user=%d userdata=%08X", + id, millis, (uint32_t)f, user, (uint32_t)userdata); gpioTimer[id].id = id; @@ -6078,7 +7200,7 @@ static int intGpioSetTimerFunc(unsigned id, gpioTimer[id].func = f; gpioTimer[id].ex = user; gpioTimer[id].userdata = userdata; - gpioTimer[id].millis = ms; + gpioTimer[id].millis = millis; if (!gpioTimer[id].running) { @@ -6113,19 +7235,19 @@ static int intGpioSetTimerFunc(unsigned id, /* ----------------------------------------------------------------------- */ -int gpioSetTimerFunc(unsigned id, unsigned ms, gpioTimerFunc_t f) +int gpioSetTimerFunc(unsigned id, unsigned millis, gpioTimerFunc_t f) { - DBG(DBG_USER, "id=%d ms=%d function=%08X", id, ms, (uint32_t)f); + DBG(DBG_USER, "id=%d millis=%d function=%08X", id, millis, (uint32_t)f); CHECK_INITED; if (id > PI_MAX_TIMER) SOFT_ERROR(PI_BAD_TIMER, "bad timer id (%d)", id); - if ((ms < PI_MIN_MS) || (ms > PI_MAX_MS)) - SOFT_ERROR(PI_BAD_MS, "timer %d, bad ms (%d)", id, ms); + if ((millis < PI_MIN_MS) || (millis > PI_MAX_MS)) + SOFT_ERROR(PI_BAD_MS, "timer %d, bad millis (%d)", id, millis); - intGpioSetTimerFunc(id, ms, f, 0, NULL); + intGpioSetTimerFunc(id, millis, f, 0, NULL); return 0; } @@ -6133,33 +7255,33 @@ int gpioSetTimerFunc(unsigned id, unsigned ms, gpioTimerFunc_t f) /* ----------------------------------------------------------------------- */ -int gpioSetTimerFuncEx(unsigned id, unsigned ms, gpioTimerFuncEx_t f, +int gpioSetTimerFuncEx(unsigned id, unsigned millis, gpioTimerFuncEx_t f, void * userdata) { - DBG(DBG_USER, "id=%d ms=%d function=%08X, userdata=%08X", - id, ms, (uint32_t)f, (uint32_t)userdata); + DBG(DBG_USER, "id=%d millis=%d function=%08X, userdata=%08X", + id, millis, (uint32_t)f, (uint32_t)userdata); CHECK_INITED; if (id > PI_MAX_TIMER) SOFT_ERROR(PI_BAD_TIMER, "bad timer id (%d)", id); - if ((ms < PI_MIN_MS) || (ms > PI_MAX_MS)) - SOFT_ERROR(PI_BAD_MS, "timer %d, bad ms (%d)", id, ms); + if ((millis < PI_MIN_MS) || (millis > PI_MAX_MS)) + SOFT_ERROR(PI_BAD_MS, "timer %d, bad millis (%d)", id, millis); - intGpioSetTimerFunc(id, ms, f, 1, userdata); + intGpioSetTimerFunc(id, millis, f, 1, userdata); return 0; } /* ----------------------------------------------------------------------- */ -pthread_t *gpioStartThread(gpioThreadFunc_t func, void *arg) +pthread_t *gpioStartThread(gpioThreadFunc_t f, void *arg) { pthread_t *pth; pthread_attr_t pthAttr; - DBG(DBG_USER, "func=%08X, arg=%08X", (uint32_t)func, (uint32_t)arg); + DBG(DBG_USER, "f=%08X, arg=%08X", (uint32_t)f, (uint32_t)arg); CHECK_INITED_RET_NULL_PTR; @@ -6179,7 +7301,7 @@ pthread_t *gpioStartThread(gpioThreadFunc_t func, void *arg) SOFT_ERROR(NULL, "pthread_attr_setstacksize failed"); } - if (pthread_create(pth, &pthAttr, func, arg)) + if (pthread_create(pth, &pthAttr, f, arg)) { free(pth); SOFT_ERROR(NULL, "pthread_create failed"); @@ -6433,7 +7555,7 @@ int gpioSetSignalFunc(unsigned signum, gpioSignalFunc_t f) /* ----------------------------------------------------------------------- */ int gpioSetSignalFuncEx(unsigned signum, gpioSignalFuncEx_t f, - void * userdata) + void *userdata) { DBG(DBG_USER, "signum=%d function=%08X userdata=%08X", signum, (uint32_t)f, (uint32_t)userdata); @@ -6478,13 +7600,13 @@ uint32_t gpioRead_Bits_32_53(void) /* ----------------------------------------------------------------------- */ -int gpioWrite_Bits_0_31_Clear(uint32_t levels) +int gpioWrite_Bits_0_31_Clear(uint32_t bits) { - DBG(DBG_USER, "levels=%08X", levels); + DBG(DBG_USER, "bits=%08X", bits); CHECK_INITED; - *(gpioReg + GPCLR0) = levels; + *(gpioReg + GPCLR0) = bits; return 0; } @@ -6492,13 +7614,13 @@ int gpioWrite_Bits_0_31_Clear(uint32_t levels) /* ----------------------------------------------------------------------- */ -int gpioWrite_Bits_32_53_Clear(uint32_t levels) +int gpioWrite_Bits_32_53_Clear(uint32_t bits) { - DBG(DBG_USER, "levels=%08X", levels); + DBG(DBG_USER, "bits=%08X", bits); CHECK_INITED; - *(gpioReg + GPCLR1) = levels; + *(gpioReg + GPCLR1) = bits; return 0; } @@ -6506,13 +7628,13 @@ int gpioWrite_Bits_32_53_Clear(uint32_t levels) /* ----------------------------------------------------------------------- */ -int gpioWrite_Bits_0_31_Set(uint32_t levels) +int gpioWrite_Bits_0_31_Set(uint32_t bits) { - DBG(DBG_USER, "levels=%08X", levels); + DBG(DBG_USER, "bits=%08X", bits); CHECK_INITED; - *(gpioReg + GPSET0) = levels; + *(gpioReg + GPSET0) = bits; return 0; } @@ -6520,13 +7642,13 @@ int gpioWrite_Bits_0_31_Set(uint32_t levels) /* ----------------------------------------------------------------------- */ -int gpioWrite_Bits_32_53_Set(uint32_t levels) +int gpioWrite_Bits_32_53_Set(uint32_t bits) { - DBG(DBG_USER, "levels=%08X", levels); + DBG(DBG_USER, "bits=%08X", bits); CHECK_INITED; - *(gpioReg + GPSET1) = levels; + *(gpioReg + GPSET1) = bits; return 0; } @@ -6534,7 +7656,7 @@ int gpioWrite_Bits_32_53_Set(uint32_t levels) /* ----------------------------------------------------------------------- */ -int gpioTime(unsigned timetype, int * seconds, int * micros) +int gpioTime(unsigned timetype, int *seconds, int *micros) { struct timespec ts; @@ -6619,7 +7741,7 @@ uint32_t gpioDelay(uint32_t micros) start = systReg[SYST_CLO]; - if (micros <= MAX_DELAY) while ((systReg[SYST_CLO] - start) <= micros) ; + if (micros <= MAX_DELAY) while ((systReg[SYST_CLO] - start) <= micros); else gpioSleep(PI_TIME_RELATIVE, (micros/MILLION), (micros%MILLION)); @@ -6730,16 +7852,16 @@ int gpioCfgClock(unsigned micros, unsigned peripheral, unsigned source) /* ----------------------------------------------------------------------- */ -int gpioCfgDMAchannel(unsigned channel) +int gpioCfgDMAchannel(unsigned DMAchannel) { - DBG(DBG_USER, "channel=%d", channel); + DBG(DBG_USER, "channel=%d", DMAchannel); CHECK_NOT_INITED; - if ((channel < PI_MIN_DMA_CHANNEL) || (channel > PI_MAX_DMA_CHANNEL)) - SOFT_ERROR(PI_BAD_CHANNEL, "bad channel (%d)", channel); + if ((DMAchannel < PI_MIN_DMA_CHANNEL) || (DMAchannel > PI_MAX_DMA_CHANNEL)) + SOFT_ERROR(PI_BAD_CHANNEL, "bad channel (%d)", DMAchannel); - gpioCfg.DMAprimaryChannel = channel; + gpioCfg.DMAprimaryChannel = DMAchannel; return 0; } @@ -6821,11 +7943,11 @@ int gpioCfgSocketPort(unsigned port) /* ----------------------------------------------------------------------- */ -int gpioCfgInternals(unsigned what, int value) +int gpioCfgInternals(unsigned cfgWhat, int cfgVal) { int retVal = PI_BAD_CFG_INTERNAL; - DBG(DBG_USER, "what=%u, value=%d", what, value); + DBG(DBG_USER, "cfgWhat=%u, cfgVal=%d", cfgWhat, cfgVal); CHECK_NOT_INITED; @@ -6844,13 +7966,13 @@ int gpioCfgInternals(unsigned what, int value) 997413601 */ - switch(what) + switch(cfgWhat) { case 562484977: - gpioCfg.showStats = value; + gpioCfg.showStats = cfgVal; - DBG(DBG_ALWAYS, "showStats is %u", value); + DBG(DBG_ALWAYS, "showStats is %u", cfgVal); retVal = 0; @@ -6858,13 +7980,13 @@ int gpioCfgInternals(unsigned what, int value) case 984762879: - if (value < DBG_ALWAYS) value = DBG_ALWAYS; + if (cfgVal < DBG_ALWAYS) cfgVal = DBG_ALWAYS; - if (value > DBG_MAX_LEVEL) value = DBG_MAX_LEVEL; + if (cfgVal > DBG_MAX_LEVEL) cfgVal = DBG_MAX_LEVEL; - gpioCfg.dbgLevel = value; + gpioCfg.dbgLevel = cfgVal; - DBG(DBG_ALWAYS, "Debug level is %u", value); + DBG(DBG_ALWAYS, "Debug level is %u", cfgVal); retVal = 0; diff --git a/pigpio.h b/pigpio.h index 012868a..dc62ca9 100644 --- a/pigpio.h +++ b/pigpio.h @@ -26,191 +26,264 @@ For more information, please refer to */ /* -This version is for pigpio version 15 +This version is for pigpio version 16 */ #ifndef PIGPIO_H #define PIGPIO_H -/************************************************************************** / -/ / -/ pigpio is a C library for the Raspberry Pi which allows / -/ control of the gpios. / -/ / -/ Its main features are: / -/ / -/ 1) provision of PWM on any number of gpios 0-31 simultaneously. / -/ 2) provision of servo pulses on any number of gpios 0-31 simultaneously. / -/ 3) callbacks when any of gpios 0-31 change state. / -/ 4) callbacks at timed intervals. / -/ 5) reading/writing all of the gpios in a bank (0-31, 32-53) as a / -/ single operation. / -/ 6) individually setting gpio modes, reading and writing. / -/ 7) notifications when any of gpios 0-31 change state. / -/ 8) the construction of arbitrary waveforms to give precise timing of / -/ output gpio level changes. / -/ 9) rudimentary permission control through the socket and pipe interfaces / -/ so users can be prevented from "updating" inappropriate gpios. / -/ 10) a simple interface to start and stop new threads. / -/ / -/ NOTE: / -/ / -/ ALL gpios are identified by their Broadcom number. / -/ / -*************************************************************************** / -/ / -/ The PWM and servo pulses are timed using the DMA and PWM peripherals. / -/ / -/ This use was inspired by Richard Hirst's servoblaster kernel module. / -/ See https://github.com/richardghirst/PiBits / -/ Tag rgh on the Raspberry Pi forums http://www.raspberrypi.org/phpBB3/ / -/ / -*************************************************************************** / -/ / -/ Usage: / -/ / -/ copy libpigpio.a to /usr/local/lib / -/ copy pigpio.h to /usr/local/include / -/ / -/ #include in your source files / -/ / -/ Assuming your source is in example.c use the following command to build / -/ / -/ gcc -o example example.c -lpigpio -lpthread -lrt / -/ / -/ For examples see checklib.c, demolib.c, pigpio.c, pigpiod.c, pig2vcd.c, / -/ and pigs.c / -/ / -****************************************************************************/ - #include #include -#define PIGPIO_VERSION 15 +#define PIGPIO_VERSION 16 -/*-------------------------------------------------------------------------*/ +/* INTRO -/* +pigpio is a C library for the Raspberry Pi which allows +control of the gpios. -Function Usage --------- ----- +Its main features are: -gpioInitialise Initialise library. -gpioTerminate Terminate library. +o PWM on any of gpios 0-31 +o servo pulses on any of gpios 0-31 +o callbacks when any of gpios 0-31 change state +o callbacks at timed intervals +o reading/writing all of the gpios in a bank as one operation +o individually setting gpio modes, reading and writing +o notifications when any of gpios 0-31 change state +o the construction of output waveforms with microsecond timing +o rudimentary permission control over gpios +o a simple interface to start and stop new threads +o I2C, SPI, and serial link wrappers -gpioSetMode Set a gpio mode. -gpioGetMode Get a gpio mode. +ALL gpios are identified by their Broadcom number. -gpioSetPullUpDown Set/clear gpio pull up/down resistor. +The PWM and servo pulses are timed using the DMA and PWM peripherals. -gpioRead Read a gpio. -gpioWrite Write a gpio. +This use was inspired by Richard Hirst's servoblaster kernel module. +See https://github.com/richardghirst/PiBits +Tag rgh on the Raspberry Pi forums http://www.raspberrypi.org/phpBB3/ -gpioPWM Start/stop PWM pulses on a gpio. +INTRO */ -gpioSetPWMrange Configure PWM range for a gpio. -gpioGetPWMrange Get configured PWM range for a gpio. -gpioGetPWMrealRange Get underlying PWM range for a gpio. +/* USAGE +Usage -gpioSetPWMfrequency Configure PWM frequency for a gpio. -gpioGetPWMfrequency Get configured PWM frequency for a gpio. +Include in your source files. -gpioServo Start/stop servo pulses on a gpio. +Assuming your source is in example.c use the following command to build -gpioSetAlertFunc Request a gpio change callback. -gpioSetAlertFuncEx Request a gpio change callback, extended. +. . +gcc -o example example.c -lpigpio -lpthread -lrt +. . -gpioNotifyOpen Open a gpio(s) changed notification. -gpioNotifyBegin Begin a gpio(s) changed notification. -gpioNotifyPause Pause a gpio(s) changed notification. -gpioNotifyClose Close a gpio(s) changed notification. +For examples see checklib.c, demolib.c, pigpio.c, pigpiod.c, pig2vcd.c, +and pigs.c -gpioWaveClear Deletes all waveforms. +All the functions which return an int return < 0 on error. -gpioWaveAddNew Starts a new waveform. -gpioWaveAddGeneric Adds a series of pulses to the waveform. -gpioWaveAddSerial Adds serial data to the waveform. +If the library isn't initialised all but the gpioCfg*, gpioVersion, +and gpioHardwareRevision functions will return error PI_NOT_INITIALISED. -gpioWaveCreate Creates a waveform from added data. -gpioWaveDelete Deletes one or more waveforms. +If the library is initialised the gpioCfg* functions will +return error PI_INITIALISED. -gpioWaveTxStart Creates/transmits a waveform (DEPRECATED). +USAGE */ -gpioWaveTxSend Transmits a waveform. -gpioWaveTxBusy Checks to see if the waveform has ended. -gpioWaveTxStop Aborts the current waveform. +/* OVERVIEW -gpioWaveGetMicros Length in microseconds of the current waveform. -gpioWaveGetHighMicros Length of longest waveform so far. -gpioWaveGetMaxMicros Absolute maximum allowed micros. +ESSENTIAL -gpioWaveGetPulses Length in pulses of the current waveform. -gpioWaveGetHighPulses Length of longest waveform so far. -gpioWaveGetMaxPulses Absolute maximum allowed pulses. +gpioInitialise Initialise library +gpioTerminate Stop library -gpioWaveGetCbs Length in cbs of the current waveform. -gpioWaveGetHighCbs Length of longest waveform so far. -gpioWaveGetMaxCbs Absolute maximum allowed cbs. +BEGINNER -gpioSerialReadOpen Opens a gpio for reading serial data. -gpioSerialRead Reads serial data from a gpio. -gpioSerialReadClose Closes a gpio for reading serial data. +gpioSetMode Set a gpio mode +gpioGetMode Get a gpio mode + +gpioSetPullUpDown Set/clear gpio pull up/down resistor + +gpioRead Read a gpio +gpioWrite Write a gpio + +gpioPWM Start/stop PWM pulses on a gpio + +gpioServo Start/stop servo pulses on a gpio + +gpioDelay Delay for a number of microseconds + +gpioSetAlertFunc Request a gpio level change callback + +gpioSetTimerFunc Request a regular timed callback + +INTERMEDIATE gpioTrigger Send a trigger pulse to a gpio. gpioSetWatchdog Set a watchdog on a gpio. -gpioSetGetSamplesFunc Requests a gpio samples callback. -gpioSetGetSamplesFuncEx Requests a gpio samples callback, extended. +gpioSetPWMrange Configure PWM range for a gpio +gpioGetPWMrange Get configured PWM range for a gpio -gpioSetTimerFunc Request a regular timed callback. -gpioSetTimerFuncEx Request a regular timed callback, extended. +gpioSetPWMfrequency Configure PWM frequency for a gpio +gpioGetPWMfrequency Get configured PWM frequency for a gpio -gpioStartThread Start a new thread. -gpioStopThread Stop a previously started thread. +gpioRead_Bits_0_31 Read all gpios in bank 1 +gpioRead_Bits_32_53 Read all gpios in bank 2 -gpioStoreScript Store a script. -gpioRunScript Run a stored script. -gpioScriptStatus Get script status and parameters. -gpioStopScript Stop a running script. -gpioDeleteScript Delete a stored script. +gpioWrite_Bits_0_31_Clear Clear selected gpios in bank 1 +gpioWrite_Bits_32_53_Clear Clear selected gpios in bank 2 -gpioSetSignalFunc Request a signal callback. -gpioSetSignalFuncEx Request a signal callback, extended. +gpioWrite_Bits_0_31_Set Set selected gpios in bank 1 +gpioWrite_Bits_32_53_Set Set selected gpios in bank 2 -gpioRead_Bits_0_31 Read gpios in bank 1. -gpioRead_Bits_32_53 Read gpios in bank 2. +gpioStartThread Start a new thread +gpioStopThread Stop a previously started thread -gpioWrite_Bits_0_31_Clear Clear gpios in bank 1. -gpioWrite_Bits_32_53_Clear Clear gpios in bank 2. +ADVANCED -gpioWrite_Bits_0_31_Set Set gpios in bank 1. -gpioWrite_Bits_32_53_Set Set gpios in bank 2. +gpioGetPWMrealRange Get underlying PWM range for a gpio -gpioTime Get current time. +gpioSetAlertFuncEx Request a gpio change callback, extended -gpioSleep Sleep for specified time. -gpioDelay Delay for microseconds. +gpioSetSignalFunc Request a signal callback +gpioSetSignalFuncEx Request a signal callback, extended -gpioTick Get current tick (microseconds). +gpioSetGetSamplesFunc Requests a gpio samples callback +gpioSetGetSamplesFuncEx Requests a gpio samples callback, extended -gpioHardwareRevision Get hardware version. +gpioSetTimerFuncEx Request a regular timed callback, extended -gpioVersion Get the pigpio version. +gpioNotifyOpen Request a notification handle +gpioNotifyBegin Start notifications for selected gpios +gpioNotifyPause Pause notifications +gpioNotifyClose Close a notification -gpioCfgBufferSize Configure the gpio sample buffer size. -gpioCfgClock Configure the gpio sample rate. -gpioCfgDMAchannel Configure the DMA channel (DEPRECATED). -gpioCfgDMAchannels Configure the DMA channels. -gpioCfgPermissions Configure the gpio access permissions. -gpioCfgInterfaces Configure user interfaces. -gpioCfgInternals Configure miscellaneous internals. -gpioCfgSocketPort Configure socket port. +gpioSerialReadOpen Opens a gpio for bit bang serial reads +gpioSerialRead Reads bit bang serial data from a gpio +gpioSerialReadClose Closes a gpio for bit bang serial reads -*/ +SCRIPTS -/*-------------------------------------------------------------------------*/ +gpioStoreScript Store a script +gpioRunScript Run a stored script +gpioScriptStatus Get script status and parameters +gpioStopScript Stop a running script +gpioDeleteScript Delete a stored script +WAVES + +gpioWaveClear Deletes all waveforms + +gpioWaveAddNew Starts a new waveform +gpioWaveAddGeneric Adds a series of pulses to the waveform +gpioWaveAddSerial Adds serial data to the waveform + +gpioWaveCreate Creates a waveform from added data +gpioWaveDelete Deletes one or more waveforms + +gpioWaveTxSend Transmits a waveform +gpioWaveTxBusy Checks to see if the waveform has ended +gpioWaveTxStop Aborts the current waveform + +gpioWaveGetMicros Length in microseconds of the current waveform +gpioWaveGetHighMicros Length of longest waveform so far +gpioWaveGetMaxMicros Absolute maximum allowed micros + +gpioWaveGetPulses Length in pulses of the current waveform +gpioWaveGetHighPulses Length of longest waveform so far +gpioWaveGetMaxPulses Absolute maximum allowed pulses + +gpioWaveGetCbs Length in cbs of the current waveform +gpioWaveGetHighCbs Length of longest waveform so far +gpioWaveGetMaxCbs Absolute maximum allowed cbs + +gpioWaveTxStart Creates/transmits a waveform (DEPRECATED) + +I2C + +i2cOpen Opens an I2C device +i2cClose Closes an I2C device + +i2cReadDevice Reads the raw I2C device +i2cWriteDevice Writes the raw I2C device + +i2cWriteQuick smbus write quick +i2cWriteByte smbus write byte +i2cReadByte smbus read byte +i2cWriteByteData smbus write byte data +i2cWriteWordData smbus write word data +i2cReadByteData smbus read byte data +i2cReadWordData smbus read word data +i2cProcessCall smbus process call +i2cWriteBlockData smbus write block data +i2cReadBlockData smbus read block data +i2cBlockProcessCall smbus block process call + +i2cWriteI2CBlockData smbus write I2C block data +i2cReadI2CBlockData smbus read I2C block data + +SPI + +spiOpen Opens a SPI device +spiClose Closes a SPI device + +spiRead Reads bytes from a SPI device +spiWrite Writes bytes to a SPI device +spiXfer Transfers bytes with a SPI device + +SERIAL + +serOpen Opens a serial device (/dev/tty*) +serClose Closes a serial device + +serWriteByte Writes a byte to a serial device +serReadByte Reads a byte from a serial device +serWrite Writes bytes to a serial device +serRead Reads bytes from a serial device + +serDataAvailable Returns number of bytes ready to be read + +CONFIGURATION + +gpioCfgBufferSize Configure the gpio sample buffer size +gpioCfgClock Configure the gpio sample rate +gpioCfgDMAchannel Configure the DMA channel (DEPRECATED) +gpioCfgDMAchannels Configure the DMA channels +gpioCfgPermissions Configure the gpio access permissions +gpioCfgInterfaces Configure user interfaces +gpioCfgInternals Configure miscellaneous internals +gpioCfgSocketPort Configure socket port + +UTILITIES + +gpioTick Get current tick (microseconds) + +gpioHardwareRevision Get hardware revision +gpioVersion Get the pigpio version + +getBitInBytes Get the value of a bit +putBitInBytes Set the value of a bit + +gpioTime Get current time +gpioSleep Sleep for specified time + +time_sleep Sleeps for a float number of seconds +time_time Float number of seconds since the epoch + +EXPERT + +rawWaveAddSPI Not intended for general use +rawWaveAddGeneric Not intended for general use +rawWaveGetOut Not intended for general use +rawWaveSetOut Not intended for general use +rawWaveGetIn Not intended for general use +rawWaveSetIn Not intended for general use +rawDumpWave Not intended for general use +rawDumpScript Not intended for general use + +OVERVIEW */ #define PI_INPFIFO "/dev/pigpio" #define PI_OUTFIFO "/dev/pigout" @@ -227,44 +300,36 @@ extern "C" { typedef struct { - uint16_t func; - uint16_t size; +uint16_t func; +uint16_t size; } gpioHeader_t; typedef struct { - uint32_t cmd; - uint32_t p1; - uint32_t p2; - uint32_t res; -} cmdCmd_t; - -typedef struct -{ - size_t size; - void *ptr; - uint32_t data; +size_t size; +void *ptr; +uint32_t data; } gpioExtent_t; typedef struct { - uint32_t tick; - uint32_t level; +uint32_t tick; +uint32_t level; } gpioSample_t; typedef struct { - uint16_t seqno; - uint16_t flags; - uint32_t tick; - uint32_t level; +uint16_t seqno; +uint16_t flags; +uint32_t tick; +uint32_t level; } gpioReport_t; typedef struct { - uint32_t gpioOn; - uint32_t gpioOff; - uint32_t usDelay; +uint32_t gpioOn; +uint32_t gpioOff; +uint32_t usDelay; } gpioPulse_t; #define WAVE_FLAG_READ 1 @@ -272,124 +337,106 @@ typedef struct typedef struct { - uint32_t gpioOn; - uint32_t gpioOff; - uint32_t usDelay; - uint32_t flags; +uint32_t gpioOn; +uint32_t gpioOff; +uint32_t usDelay; +uint32_t flags; } rawWave_t; typedef struct { - int clk; /* gpio for clock */ - int mosi; /* gpio for MOSI */ - int miso; /* gpio for MISO */ - int ss_pol; /* slave select off state */ - int ss_us; /* delay after slave select */ - int clk_pol; /* clock off state */ - int clk_pha; /* clock phase */ - int clk_us; /* clock micros */ +int clk; /* gpio for clock */ +int mosi; /* gpio for MOSI */ +int miso; /* gpio for MISO */ +int ss_pol; /* slave select off state */ +int ss_us; /* delay after slave select */ +int clk_pol; /* clock off state */ +int clk_pha; /* clock phase */ +int clk_us; /* clock micros */ } rawSPI_t; typedef struct { /* linux/arch/arm/mach-bcm2708/include/mach/dma.h */ - unsigned long info; - unsigned long src; - unsigned long dst; - unsigned long length; - unsigned long stride; - unsigned long next; - unsigned long pad[2]; +unsigned long info; +unsigned long src; +unsigned long dst; +unsigned long length; +unsigned long stride; +unsigned long next; +unsigned long pad[2]; } rawCbs_t; typedef void (*gpioAlertFunc_t) (int gpio, - int level, - uint32_t tick); + int level, + uint32_t tick); typedef void (*gpioAlertFuncEx_t) (int gpio, - int level, - uint32_t tick, - void * userdata); + int level, + uint32_t tick, + void *userdata); typedef void (*gpioTimerFunc_t) (void); -typedef void (*gpioTimerFuncEx_t) (void * userdata); +typedef void (*gpioTimerFuncEx_t) (void *userdata); typedef void (*gpioSignalFunc_t) (int signum); typedef void (*gpioSignalFuncEx_t) (int signum, - void * userdata); + void *userdata); -typedef void (*gpioGetSamplesFunc_t) (const gpioSample_t * samples, - int numSamples); +typedef void (*gpioGetSamplesFunc_t) (const gpioSample_t *samples, + int numSamples); -typedef void (*gpioGetSamplesFuncEx_t) (const gpioSample_t * samples, - int numSamples, - void * userdata); +typedef void (*gpioGetSamplesFuncEx_t) (const gpioSample_t *samples, + int numSamples, + void *userdata); typedef void *(gpioThreadFunc_t) (void *); -/* - All the functions which return an int return < 0 on error. - - If the library isn't initialised all but the gpioCfg*, gpioVersion, - and gpioHardwareRevision functions will return error PI_NOT_INITIALISED. - - If the library is initialised the gpioCfg* functions will - return error PI_INITIALISED. -*/ - - - -/*-------------------------------------------------------------------------*/ +/* FUNC */ int gpioInitialise(void); -/*-------------------------------------------------------------------------*/ -/* Initialises the library. +/* DESC +Initialises the library. - Call before using the other library functions. +Call before using the other library functions. - Returns the pigpio version number if OK, otherwise PI_INIT_FAILED. +Returns the pigpio version number if OK, otherwise PI_INIT_FAILED. - NOTES: - - The only exception is the optional gpioCfg* functions, see later. -*/ +The only exception is the optional gpioCfg* functions, see later. +DESC */ -/*-------------------------------------------------------------------------*/ +/* FUNC */ void gpioTerminate(void); -/*-------------------------------------------------------------------------*/ -/* Terminates the library. +/* DESC +Terminates the library. - Returns nothing. +Returns nothing. - Call before program exit. +Call before program exit. - NOTES: - - This function resets the DMA and PWM peripherals, releases memory, and - terminates any running threads. -*/ +This function resets the DMA and PWM peripherals, releases memory, and +terminates any running threads. +DESC */ -/*-------------------------------------------------------------------------*/ -int gpioSetMode(unsigned gpio, - unsigned mode); -/*-------------------------------------------------------------------------*/ -/* Sets the gpio mode, typically input or output. +/* FUNC */ +int gpioSetMode(unsigned gpio, unsigned mode); +/* DESC +Sets the gpio mode, typically input or output. - Returns 0 if OK, otherwise PI_BAD_GPIO or PI_BAD_MODE. +Returns 0 if OK, otherwise PI_BAD_GPIO or PI_BAD_MODE. - Arduino style: pinMode. +Arduino style: pinMode. - EXAMPLE: - ... - gpioSetMode(17, PI_INPUT); // set gpio17 as input - gpioSetMode(18, PI_OUTPUT); // set gpio18 as output - gpioSetMode(22,PI_ALT0); // set gpio22 to alternative mode 0 - ... -*/ +... +gpioSetMode(17, PI_INPUT); // set gpio17 as input +gpioSetMode(18, PI_OUTPUT); // set gpio18 as output +gpioSetMode(22,PI_ALT0); // set gpio22 to alternative mode 0 +... +DESC */ /* gpio: 0-53 */ @@ -409,39 +456,36 @@ int gpioSetMode(unsigned gpio, -/*-------------------------------------------------------------------------*/ +/* FUNC */ int gpioGetMode(unsigned gpio); -/*-------------------------------------------------------------------------*/ -/* Gets the gpio mode. +/* DESC +Gets the gpio mode. - Returns the gpio mode if OK, otherwise PI_BAD_GPIO. +Returns the gpio mode if OK, otherwise PI_BAD_GPIO. - EXAMPLE: - ... - if (gpioGetMode(17) != PI_ALT0) - { - gpioSetMode(17, PI_ALT0); // set gpio17 to ALT0 - } - ... -*/ +... +if (gpioGetMode(17) != PI_ALT0) +{ + gpioSetMode(17, PI_ALT0); // set gpio17 to ALT0 +} +... +DESC */ -/*-------------------------------------------------------------------------*/ -int gpioSetPullUpDown(unsigned gpio, - unsigned pud); -/*-------------------------------------------------------------------------*/ -/* Sets or clears resistor pull ups or downs on the gpio. +/* FUNC */ +int gpioSetPullUpDown(unsigned gpio, unsigned pud); +/* DESC +Sets or clears resistor pull ups or downs on the gpio. - Returns 0 if OK, otherwise PI_BAD_GPIO or PI_BAD_PUD. +Returns 0 if OK, otherwise PI_BAD_GPIO or PI_BAD_PUD. - EXAMPLE: - ... - gpioSetPullUpDown(17, PI_PUD_UP); // sets a pull-up on gpio17 - gpioSetPullUpDown(18, PI_PUD_DOWN); // sets a pull-down on gpio18 - gpioSetPullUpDown(23, PI_PUD_OFF); // clear pull-ups/downs on gpio23 - ... -*/ +... +gpioSetPullUpDown(17, PI_PUD_UP); // sets a pull-up on gpio17 +gpioSetPullUpDown(18, PI_PUD_DOWN); // sets a pull-down on gpio18 +gpioSetPullUpDown(23, PI_PUD_OFF); // clear pull-ups/downs on gpio23 +... +DESC */ /* pud: 0-2 */ @@ -451,22 +495,19 @@ int gpioSetPullUpDown(unsigned gpio, -/*-------------------------------------------------------------------------*/ +/* FUNC */ int gpioRead (unsigned gpio); -/*-------------------------------------------------------------------------*/ -/* Reads the gpio level, on or off. +/* DESC +Reads the gpio level, on or off. - Returns the gpio level if OK, otherwise PI_BAD_GPIO. +Returns the gpio level if OK, otherwise PI_BAD_GPIO. - EXAMPLE: - ... - printf("gpio24 is level %d\n", gpioRead(24)); - ... +Arduino style: digitalRead. - NOTES: - - Arduino style: digitalRead. -*/ +... +printf("gpio24 is level %d\n", gpioRead(24)); +... +DESC */ /* level: 0-1 */ @@ -485,53 +526,45 @@ int gpioRead (unsigned gpio); -/*-------------------------------------------------------------------------*/ -int gpioWrite(unsigned gpio, - unsigned level); -/*-------------------------------------------------------------------------*/ -/* Sets the gpio level, on or off. +/* FUNC */ +int gpioWrite(unsigned gpio, unsigned level); +/* DESC +Sets the gpio level, on or off. - Returns 0 if OK, otherwise PI_BAD_GPIO or PI_BAD_LEVEL. +Returns 0 if OK, otherwise PI_BAD_GPIO or PI_BAD_LEVEL. - EXAMPLE: - ... - gpioWrite(24, 1); // sets gpio24 high - ... +If PWM or servo pulses are active on the gpio they are switched off. - NOTES: +Arduino style: digitalWrite - If PWM or servo pulses are active on the gpio they are switched off. - - Arduino style: digitalWrite -*/ +... +gpioWrite(24, 1); // sets gpio24 high +... +DESC */ -/*-------------------------------------------------------------------------*/ -int gpioPWM(unsigned user_gpio, - unsigned dutycycle); -/*-------------------------------------------------------------------------*/ -/* Starts PWM on the gpio, dutycycle between 0 (off) and range (fully on). - Range defaults to 255. +/* FUNC */ +int gpioPWM(unsigned user_gpio, unsigned dutycycle); +/* DESC +Starts PWM on the gpio, dutycycle between 0 (off) and range (fully on). +Range defaults to 255. - Returns 0 if OK, otherwise PI_BAD_USER_GPIO or PI_BAD_DUTYCYCLE. +Returns 0 if OK, otherwise PI_BAD_USER_GPIO or PI_BAD_DUTYCYCLE. - EXAMPLE: - ... - gpioPWM(17, 255); // sets gpio17 full on - gpioPWM(18, 128); // sets gpio18 half on - gpioPWM(23, 0); // sets gpio23 full off - ... +Arduino style: analogWrite - NOTES: +This and the servo functionality use the DMA and PWM or PCM peripherals +to control and schedule the pulse lengths and duty cycles. - Arduino style: analogWrite +The gpioSetPWMrange funtion can change the default range of 255. - This and the servo functionality use the DMA and PWM or PCM peripherals - to control and schedule the pulse lengths and duty cycles. - - The gpioSetPWMrange funtion can change the default range of 255. -*/ +... +gpioPWM(17, 255); // sets gpio17 full on +gpioPWM(18, 128); // sets gpio18 half on +gpioPWM(23, 0); // sets gpio23 full off +... +DESC */ /* user_gpio: 0-31 */ @@ -543,36 +576,34 @@ int gpioPWM(unsigned user_gpio, -/*-------------------------------------------------------------------------*/ -int gpioSetPWMrange(unsigned user_gpio, - unsigned range); -/*-------------------------------------------------------------------------*/ -/* Selects the dutycycle range to be used for the gpio. Subsequent calls - to gpioPWM will use a dutycycle between 0 (off) and range (fully on). +/* FUNC */ +int gpioSetPWMrange(unsigned user_gpio, unsigned range); +/* DESC +Selects the dutycycle range to be used for the gpio. Subsequent calls +to gpioPWM will use a dutycycle between 0 (off) and range (fully on). - Returns the real range for the given gpio's frequency if OK, - otherwise PI_BAD_USER_GPIO or PI_BAD_DUTYRANGE. +Returns the real range for the given gpio's frequency if OK, +otherwise PI_BAD_USER_GPIO or PI_BAD_DUTYRANGE. - EXAMPLE: - ... - gpioSetPWMrange(24, 2000); // now 2000 is fully on, 1000 is half on etc. - ... +If PWM is currently active on the gpio its dutycycle will be scaled +to reflect the new range. - NOTES: +The real range, the number of steps between fully off and fully +on for each frequency, is given in the following table. - If PWM is currently active on the gpio its dutycycle will be scaled - to reflect the new range. +. . + 25, 50, 100, 125, 200, 250, 400, 500, 625, + 800, 1000, 1250, 2000, 2500, 4000, 5000, 10000, 20000 +. . - The real range, the number of steps between fully off and fully - on for each frequency, is given in the following table. +The real value set by gpioPWM is - 25, 50, 100, 125, 200, 250, 400, 500, 625, - 800, 1000, 1250, 2000, 2500, 4000, 5000, 10000, 20000 +(dutycycle * real range) / range. - The real value set by gpioPWM is - - (dutycycle * real range) / range. -*/ +... +gpioSetPWMrange(24, 2000); // now 2000 is fully on, 1000 is half on etc. +... +DESC */ /* range: 25-40000 */ @@ -581,130 +612,126 @@ int gpioSetPWMrange(unsigned user_gpio, -/*-------------------------------------------------------------------------*/ +/* FUNC */ int gpioGetPWMrange(unsigned user_gpio); -/*-------------------------------------------------------------------------*/ -/* Returns the dutycycle range used for the gpio if OK, otherwise - PI_BAD_USER_GPIO. -*/ +/* DESC +Returns the dutycycle range used for the gpio if OK, otherwise +PI_BAD_USER_GPIO. +DESC */ -/*-------------------------------------------------------------------------*/ +/* FUNC */ int gpioGetPWMrealRange(unsigned user_gpio); -/*-------------------------------------------------------------------------*/ -/* Returns the real range used for the gpio if OK, otherwise - PI_BAD_USER_GPIO. -*/ +/* DESC +Returns the real range used for the gpio if OK, otherwise +PI_BAD_USER_GPIO. +DESC */ -/*-------------------------------------------------------------------------*/ -int gpioSetPWMfrequency(unsigned user_gpio, - unsigned frequency); -/*-------------------------------------------------------------------------*/ -/* Sets the frequency in hertz to be used for the gpio. +/* FUNC */ +int gpioSetPWMfrequency(unsigned user_gpio, unsigned frequency); +/* DESC +Sets the frequency in hertz to be used for the gpio. - Returns the numerically closest frequency if OK, otherwise - PI_BAD_USER_GPIO. +Returns the numerically closest frequency if OK, otherwise +PI_BAD_USER_GPIO. - The selectable frequencies depend upon the sample rate which - may be 1, 2, 4, 5, 8, or 10 microseconds (default 5). +The selectable frequencies depend upon the sample rate which +may be 1, 2, 4, 5, 8, or 10 microseconds (default 5). - Each gpio can be independently set to one of 18 different PWM - frequencies. +Each gpio can be independently set to one of 18 different PWM +frequencies. - If PWM is currently active on the gpio it will be - switched off and then back on at the new frequency. +If PWM is currently active on the gpio it will be +switched off and then back on at the new frequency. - NOTES: +The frequencies for each sample rate are: - The frequencies for each sample rate are: - - Hertz +. . + Hertz 1: 40000 20000 10000 8000 5000 4000 2500 2000 1600 - 1250 1000 800 500 400 250 200 100 50 + 1250 1000 800 500 400 250 200 100 50 2: 20000 10000 5000 4000 2500 2000 1250 1000 800 - 625 500 400 250 200 125 100 50 25 + 625 500 400 250 200 125 100 50 25 4: 10000 5000 2500 2000 1250 1000 625 500 400 - 313 250 200 125 100 63 50 25 13 + 313 250 200 125 100 63 50 25 13 sample rate (us) 5: 8000 4000 2000 1600 1000 800 500 400 320 - 250 200 160 100 80 50 40 20 10 + 250 200 160 100 80 50 40 20 10 8: 5000 2500 1250 1000 625 500 313 250 200 - 156 125 100 63 50 31 25 13 6 + 156 125 100 63 50 31 25 13 6 10: 4000 2000 1000 800 500 400 250 200 160 125 100 80 50 40 25 20 10 5 -*/ +. . +DESC */ -/*-------------------------------------------------------------------------*/ +/* FUNC */ int gpioGetPWMfrequency(unsigned user_gpio); -/*-------------------------------------------------------------------------*/ -/* Returns the frequency (in hertz) used for the gpio if OK, otherwise - PI_BAD_USER_GPIO. -*/ +/* DESC +Returns the frequency (in hertz) used for the gpio if OK, otherwise +PI_BAD_USER_GPIO. +DESC */ -/*-------------------------------------------------------------------------*/ -int gpioServo(unsigned user_gpio, - unsigned pulsewidth); -/*-------------------------------------------------------------------------*/ -/* Starts servo pulses on the gpio, 0 (off), 500 (most anti-clockwise) to - 2500 (most clockwise). +/* FUNC */ +int gpioServo(unsigned user_gpio, unsigned pulsewidth); +/* DESC +Starts servo pulses on the gpio, 0 (off), 500 (most anti-clockwise) to +2500 (most clockwise). - Returns 0 if OK, otherwise PI_BAD_USER_GPIO or PI_BAD_PULSEWIDTH. +Returns 0 if OK, otherwise PI_BAD_USER_GPIO or PI_BAD_PULSEWIDTH. - NOTES: +The range supported by servos varies and should probably be determined +by experiment. A value of 1500 should always be safe and represents +the mid-point of rotation. You can DAMAGE a servo if you command it +to move beyond its limits. - The range supported by servos varies and should probably be determined - by experiment. A value of 1500 should always be safe and represents - the mid-point of rotation. You can DAMAGE a servo if you command it - to move beyond its limits. +The following causes an on pulse of 1500 microseconds duration to be +transmitted on gpio 17 at a rate of 50 times per second. This will + command a servo connected to gpio 17 to rotate to its mid-point. - EXAMPLE: +... +gpioServo(17, 1500); +... - ... - gpioServo(17, 1500); - ... +OTHER UPDATE RATES: - This example causes an on pulse of 1500 microseconds duration to be - transmitted on gpio 17 at a rate of 50 times per second. +This function updates servos at 50Hz. If you wish to use a different +update frequency you will have to use the PWM functions. - This will command a servo connected to gpio 17 to rotate to - its mid-point. +. . +PWM Hz 50 100 200 400 500 +1E6/Hz 20000 10000 5000 2500 2000 +. . - OTHER UPDATE RATES: +Firstly set the desired PWM frequency using gpioSetPWMfrequency. - This function updates servos at 50Hz. If you wish to use a different - update frequency you will have to use the PWM functions. +Then set the PWM range using gpioSetPWMrange to 1E6/frequency. +Doing this allows you to use units of microseconds when setting +the servo pulse width. - PWM Hz 50 100 200 400 500 - 1E6/Hz 20000 10000 5000 2500 2000 +E.g. If you want to update a servo connected to gpio 25 at 400Hz - Firstly set the desired PWM frequency using gpioSetPWMfrequency. +. . +gpioSetPWMfrequency(25, 400); +gpioSetPWMrange(25, 2500); +. . - Then set the PWM range using gpioSetPWMrange to 1E6/frequency. - Doing this allows you to use units of microseconds when setting - the servo pulse width. +Thereafter use the PWM command to move the servo, +e.g. gpioPWM(25, 1500) will set a 1500 us pulse. - E.g. If you want to update a servo connected to gpio 25 at 400Hz - - gpioSetPWMfrequency(25, 400); - gpioSetPWMrange(25, 2500); - - Thereafter use the PWM command to move the servo, - e.g. gpioPWM(25, 1500) will set a 1500 us pulse. - -*/ +DESC */ /* pulsewidth: 0, 500-2500 */ @@ -713,248 +740,240 @@ int gpioServo(unsigned user_gpio, #define PI_MAX_SERVO_PULSEWIDTH 2500 -/*-------------------------------------------------------------------------*/ -int gpioSetAlertFunc(unsigned user_gpio, - gpioAlertFunc_t f); -/*-------------------------------------------------------------------------*/ -/* Registers a function to be called (a callback) when the specified - gpio changes state. +/* FUNC */ +int gpioSetAlertFunc(unsigned user_gpio, gpioAlertFunc_t f); +/* DESC +Registers a function to be called (a callback) when the specified +gpio changes state. - Returns 0 if OK, otherwise PI_BAD_USER_GPIO. +Returns 0 if OK, otherwise PI_BAD_USER_GPIO. - One function may be registered per gpio. +One function may be registered per gpio. - The function is passed the gpio, the new level, and the tick. +The function is passed the gpio, the new level, and the tick. - The alert may be cancelled by passing NULL as the function. +The alert may be cancelled by passing NULL as the function. - EXAMPLE: - ... - void aFunction(int gpio, int level, uint32_t tick) - { - printf("gpio %d became %d at %d\n", gpio, level, tick); - } - ... - gpioSetAlertFunc(4, aFunction); - ... +The gpios are sampled at a rate set when the library is started. - This example causes aFunction to be called whenever - gpio 4 changes state. +If a value isn't specifically set the default of 5 us is used. - NOTES: +The number of samples per second is given in the following table. - The gpios are sampled at a rate set when the library is started. +. . + samples + per sec - If a value isn't specifically set the default of 5 us is used. + 1 1,000,000 + 2 500,000 +sample 4 250,000 +rate 5 200,000 +(us) 8 125,000 + 10 100,000 +. . - The number of samples per second is given in the following table. +Level changes of length less than the sample rate may be missed. - samples - per sec +The thread which calls the alert functions is triggered nominally +1000 times per second. The active alert functions will be called +once per level change since the last time the thread was activated. +i.e. The active alert functions will get all level changes but there +will be a latency. - 1 1,000,000 - 2 500,000 - sample 4 250,000 - rate 5 200,000 - (us) 8 125,000 - 10 100,000 +The tick value is the time stamp of the sample in microseconds, see +gpioTick for more details. - Level changes of length less than the sample rate may be missed. +... +void aFunction(int gpio, int level, uint32_t tick) +{ + printf("gpio %d became %d at %d\n", gpio, level, tick); +} - The thread which calls the alert functions is triggered nominally - 1000 times per second. The active alert functions will be called - once per level change since the last time the thread was activated. - i.e. The active alert functions will get all level changes but there - will be a latency. - - The tick value is the time stamp of the sample in microseconds, see - gpioTick for more details. -*/ +// call aFunction whenever gpio 4 changes state +gpioSetAlertFunc(4, aFunction); +... +DESC */ -/*-------------------------------------------------------------------------*/ -int gpioSetAlertFuncEx(unsigned user_gpio, - gpioAlertFuncEx_t f, - void * userdata); -/*-------------------------------------------------------------------------*/ -/* Registers a function to be called (a callback) when the specified - gpio changes state. +/* FUNC */ +int gpioSetAlertFuncEx( + unsigned user_gpio, gpioAlertFuncEx_t f, void *userdata); +/* DESC +Registers a function to be called (a callback) when the specified +gpio changes state. - Returns 0 if OK, otherwise PI_BAD_USER_GPIO. +Returns 0 if OK, otherwise PI_BAD_USER_GPIO. - One function may be registered per gpio. +One function may be registered per gpio. - The function is passed the gpio, the new level, the tick, and - the userdata pointer. +The function is passed the gpio, the new level, the tick, and +the userdata pointer. - Only one of gpioSetAlertFunc or gpioSetAlertFuncEx can be - registered per gpio. +Only one of gpioSetAlertFunc or gpioSetAlertFuncEx can be +registered per gpio. - See gpioSetAlertFunc for further details. -*/ +See gpioSetAlertFunc for further details. +DESC */ -/*-------------------------------------------------------------------------*/ +/* FUNC */ int gpioNotifyOpen(void); -/*-------------------------------------------------------------------------*/ -/* This function requests a free notification handle. +/* DESC +This function requests a free notification handle. - Returns a handle greater than or equal to zero if OK, - otherwise PI_NO_HANDLE. +Returns a handle greater than or equal to zero if OK, +otherwise PI_NO_HANDLE. - A notification is a method for being notified of gpio state changes - via a pipe or socket. +A notification is a method for being notified of gpio state changes +via a pipe or socket. - Pipe notifications for handle x will be available at the pipe - named /dev/pigpiox (where x is the handle number). E.g. if the - function returns 15 then the notifications must be read - from /dev/pigpio15. +Pipe notifications for handle x will be available at the pipe +named /dev/pigpiox (where x is the handle number). E.g. if the +function returns 15 then the notifications must be read +from /dev/pigpio15. - Socket notifications are returned to the socket which requested the - handle. -*/ +Socket notifications are returned to the socket which requested the +handle. +DESC */ #define PI_NOTIFY_SLOTS 32 -/*-------------------------------------------------------------------------*/ -int gpioNotifyBegin(unsigned handle, - uint32_t bits); -/*-------------------------------------------------------------------------*/ -/* This function starts notifications on a previously opened handle. +/* FUNC */ +int gpioNotifyBegin(unsigned handle, uint32_t bits); +/* DESC +This function starts notifications on a previously opened handle. - Returns 0 if OK, otherwise PI_BAD_HANDLE. +Returns 0 if OK, otherwise PI_BAD_HANDLE. - The notification sends state changes for each gpio whose corresponding - bit in bits is set. +The notification sends state changes for each gpio whose corresponding +bit in bits is set. - EXAMPLE: +Each notification occupies 12 bytes in the fifo and has the +following structure. - gpioNotifyBegin(0, 1234) will start notifications for gpios 1, 4, 6, - 7, 10 (1234 = 0x04D2 = 0b0000010011010010). +. . +typedef struct +{ + uint16_t seqno; + uint16_t flags; + uint32_t tick; + uint32_t level; +} gpioReport_t; +. . - NOTES: +seqno starts at 0 each time the handle is opened and then increments +by one for each report. - Each notification occupies 12 bytes in the fifo and has the - following structure. +flags, if bit 5 is set then bits 0-4 of the flags indicate a gpio +which has had a watchdog timeout. - typedef struct - { - uint16_t seqno; - uint16_t flags; - uint32_t tick; - uint32_t level; - } gpioReport_t; +tick is the number of microseconds since system boot. - seqno starts at 0 each time the handle is opened and then increments - by one for each report. +level indicates the level of each gpio. - flags, if bit 5 is set then bits 0-4 of the flags indicate a gpio - which has had a watchdog timeout. +... +// start notifications for gpios 1, 4, 6, 7, 10 +// (1234 = 0x04D2 = 0b0000010011010010) - tick is the number of microseconds since system boot. - - level indicates the level of each gpio. -*/ +gpioNotifyBegin(0, 1234); +... +DESC */ #define PI_NTFY_FLAGS_WDOG (1 <<5) #define PI_NTFY_FLAGS_BIT(x) (((x)<<0)&31) -/*-------------------------------------------------------------------------*/ +/* FUNC */ int gpioNotifyPause(unsigned handle); -/*-------------------------------------------------------------------------*/ -/* This function pauses notifications on a previously opened handle. +/* DESC +This function pauses notifications on a previously opened handle. - Returns 0 if OK, otherwise PI_BAD_HANDLE. +Returns 0 if OK, otherwise PI_BAD_HANDLE. - Notifications for the handle are suspended until gpioNotifyBegin - is called again. -*/ +Notifications for the handle are suspended until gpioNotifyBegin +is called again. +DESC */ -/*-------------------------------------------------------------------------*/ +/* FUNC */ int gpioNotifyClose(unsigned handle); -/*-------------------------------------------------------------------------*/ -/* This function stops notifications on a previously opened handle - and releases the handle for reuse. +/* DESC +This function stops notifications on a previously opened handle +and releases the handle for reuse. - Returns 0 if OK, otherwise PI_BAD_HANDLE. -*/ +Returns 0 if OK, otherwise PI_BAD_HANDLE. +DESC */ -/*-------------------------------------------------------------------------*/ +/* FUNC */ int gpioWaveClear(void); -/*-------------------------------------------------------------------------*/ -/* This function clears all waveforms and any data added by calls to the - gpioWaveAdd* functions. +/* DESC +This function clears all waveforms and any data added by calls to the +gpioWaveAdd* functions. - Returns 0 if OK. -*/ +Returns 0 if OK. +DESC */ -/*-------------------------------------------------------------------------*/ +/* FUNC */ int gpioWaveAddNew(void); -/*-------------------------------------------------------------------------*/ -/* This function starts a new empty waveform. You wouldn't normally need - to call this function as it is automatically called after a waveform is - created with the gpioWaveCreate function. +/* DESC +This function starts a new empty waveform. You wouldn't normally need +to call this function as it is automatically called after a waveform is +created with the gpioWaveCreate function. - Returns 0 if OK. -*/ +Returns 0 if OK. +DESC */ -/*-------------------------------------------------------------------------*/ -int gpioWaveAddGeneric(unsigned numPulses, gpioPulse_t * pulses); -/*-------------------------------------------------------------------------*/ -/* This function adds a number of pulses to the current waveform. +/* FUNC */ +int gpioWaveAddGeneric(unsigned numPulses, gpioPulse_t *pulses); +/* DESC +This function adds a number of pulses to the current waveform. - Returns the new total number of pulses in the current waveform if OK, - otherwise PI_TOO_MANY_PULSES. +Returns the new total number of pulses in the current waveform if OK, +otherwise PI_TOO_MANY_PULSES. - NOTES: +The pulses are interleaved in time order within the existing waveform +(if any). - The pulses are interleaved in time order within the existing waveform - (if any). +Merging allows the waveform to be built in parts, that is the settings +for gpio#1 can be added, and then gpio#2 etc. - Merging allows the waveform to be built in parts, that is the settings - for gpio#1 can be added, and then gpio#2 etc. - - If the added waveform is intended to start after or within the existing - waveform then the first pulse should consist of a delay. -*/ +If the added waveform is intended to start after or within the existing +waveform then the first pulse should consist of a delay. +DESC */ -/*-------------------------------------------------------------------------*/ +/* FUNC */ int gpioWaveAddSerial(unsigned user_gpio, - unsigned baud, + unsigned bbBaud, unsigned offset, unsigned numChar, - char * str); -/*-------------------------------------------------------------------------*/ -/* This function adds a waveform representing serial data to the - existing waveform (if any). The serial data starts offset microseconds - from the start of the waveform. + char *str); +/* DESC +This function adds a waveform representing serial data to the +existing waveform (if any). The serial data starts offset microseconds +from the start of the waveform. - Returns the new total number of pulses in the current waveform if OK, - otherwise PI_BAD_USER_GPIO, PI_BAD_WAVE_BAUD, PI_TOO_MANY_CHARS, - PI_BAD_SER_OFFSET, or PI_TOO_MANY_PULSES. +Returns the new total number of pulses in the current waveform if OK, +otherwise PI_BAD_USER_GPIO, PI_BAD_WAVE_BAUD, PI_TOO_MANY_CHARS, +PI_BAD_SER_OFFSET, or PI_TOO_MANY_PULSES. - NOTES: +The serial data is formatted as one start bit, eight data bits, and one +stop bit. - The serial data is formatted as one start bit, eight data bits, and one - stop bit. - - It is legal to add serial data streams with different baud rates to - the same waveform. -*/ +It is legal to add serial data streams with different baud rates to +the same waveform. +DESC */ #define PI_WAVE_BLOCKS 4 #define PI_WAVE_MAX_PULSES (PI_WAVE_BLOCKS * 3000) @@ -965,294 +984,613 @@ int gpioWaveAddSerial(unsigned user_gpio, #define PI_WAVE_MAX_MICROS (30 * 60 * 1000000) /* half an hour */ -#define PI_MAX_WAVES 100 +#define PI_MAX_WAVES 512 - -/*-------------------------------------------------------------------------*/ +/* FUNC */ int gpioWaveCreate(void); -/*-------------------------------------------------------------------------*/ -/* This function creates a waveform from the data provided by the prior - calls to the gpioWaveAdd* functions. Upon success a positive wave id - is returned. +/* DESC +This function creates a waveform from the data provided by the prior +calls to the gpioWaveAdd* functions. Upon success a positive wave id +is returned. - The data provided by the gpioWaveAdd* functions is consumed by this - function. +The data provided by the gpioWaveAdd* functions is consumed by this +function. - As many waveforms may be created as there is space available. The - wave id is passed to gpioWaveTxSend to specify the waveform to transmit. +As many waveforms may be created as there is space available. The +wave id is passed to gpioWaveTxSend to specify the waveform to transmit. - Normal usage would be +Normal usage would be - Step 1. gpioWaveClear to clear all waveforms and added data. +Step 1. gpioWaveClear to clear all waveforms and added data. - Step 2. gpioWaveAdd* calls to supply the waveform data. +Step 2. gpioWaveAdd* calls to supply the waveform data. - Step 3. gpioWaveCreate to create the waveform and get a unique id +Step 3. gpioWaveCreate to create the waveform and get a unique id - Repeat steps 2 and 3 as needed. +Repeat steps 2 and 3 as needed. - Step 4. gpioWaveTxSend with the id of the waveform to transmit. +Step 4. gpioWaveTxSend with the id of the waveform to transmit. - A waveform comprises one of more pulses. Each pulse consists of a - gpioPulse_t structure. +A waveform comprises one of more pulses. Each pulse consists of a +gpioPulse_t structure. - typedef struct - { - uint32_t gpioOn; - uint32_t gpioOff; - uint32_t usDelay; - } gpioPulse_t; +typedef struct +{ + uint32_t gpioOn; + uint32_t gpioOff; + uint32_t usDelay; +} gpioPulse_t; - The fields specify +The fields specify - 1) the gpios to be switched on at the start of the pulse. - 2) the gpios to be switched off at the start of the pulse. - 3) the delay in microseconds before the next pulse. +1) the gpios to be switched on at the start of the pulse. +2) the gpios to be switched off at the start of the pulse. +3) the delay in microseconds before the next pulse. - Any or all the fields can be zero. It doesn't make any sense to - set all the fields to zero (the pulse will be ignored). +Any or all the fields can be zero. It doesn't make any sense to +set all the fields to zero (the pulse will be ignored). - When a waveform is started each pulse is executed in order with the - specified delay between the pulse and the next. +When a waveform is started each pulse is executed in order with the +specified delay between the pulse and the next. - Returns the new waveform id if OK, otherwise PI_EMPTY_WAVEFORM, - PI_NO_WAVEFORM_ID, PI_TOO_MANY_CBS, or PI_TOO_MANY_OOL. -*/ +Returns the new waveform id if OK, otherwise PI_EMPTY_WAVEFORM, +PI_NO_WAVEFORM_ID, PI_TOO_MANY_CBS, or PI_TOO_MANY_OOL. +DESC */ -/*-------------------------------------------------------------------------*/ +/* FUNC */ int gpioWaveDelete(unsigned wave_id); -/*-------------------------------------------------------------------------*/ -/* This function deletes all created waveforms with ids greater than or - equal to wave_id. +/* DESC +This function deletes all created waveforms with ids greater than or +equal to wave_id. - Wave ids are allocated in order, 0, 1, 2, etc. +Wave ids are allocated in order, 0, 1, 2, etc. - Returns 0 if OK, otherwise PI_BAD_WAVE_ID. -*/ +Returns 0 if OK, otherwise PI_BAD_WAVE_ID. +DESC */ -/*-------------------------------------------------------------------------*/ +/* FUNC */ int gpioWaveTxStart(unsigned mode); /* DEPRECATED */ -/*-------------------------------------------------------------------------*/ -/* This function creates and then transmits a waveform. The mode - determines whether the waveform is sent once or cycles endlessly. +/* DESC +This function creates and then transmits a waveform. The mode +determines whether the waveform is sent once or cycles endlessly. - This function is deprecated and should no longer be used. Use - gpioWaveCreate/gpioWaveTxSend instead. +This function is deprecated and should no longer be used. Use +gpioWaveCreate/gpioWaveTxSend instead. - Returns the number of DMA control blocks in the waveform if OK, - otherwise PI_BAD_WAVE_MODE. -*/ +Returns the number of DMA control blocks in the waveform if OK, +otherwise PI_BAD_WAVE_MODE. +DESC */ -/*-------------------------------------------------------------------------*/ +/* FUNC */ int gpioWaveTxSend(unsigned wave_id, unsigned mode); -/*-------------------------------------------------------------------------*/ -/* This function transmits the waveform with id wave_id. The mode - determines whether the waveform is sent once or cycles endlessly. +/* DESC +This function transmits the waveform with id wave_id. The mode +determines whether the waveform is sent once or cycles endlessly. - Returns the number of DMA control blocks in the waveform if OK, - otherwise PI_BAD_WAVE_ID, or PI_BAD_WAVE_MODE. -*/ +Returns the number of DMA control blocks in the waveform if OK, +otherwise PI_BAD_WAVE_ID, or PI_BAD_WAVE_MODE. +DESC */ #define PI_WAVE_MODE_ONE_SHOT 0 #define PI_WAVE_MODE_REPEAT 1 -/*-------------------------------------------------------------------------*/ +/* FUNC */ int gpioWaveTxBusy(void); -/*-------------------------------------------------------------------------*/ -/* This function checks to see if a waveform is currently being - transmitted. +/* DESC +This function checks to see if a waveform is currently being +transmitted. - Returns 1 if a waveform is currently being transmitted, otherwise 0. -*/ +Returns 1 if a waveform is currently being transmitted, otherwise 0. +DESC */ -/*-------------------------------------------------------------------------*/ +/* FUNC */ int gpioWaveTxStop(void); -/*-------------------------------------------------------------------------*/ -/* This function aborts the transmission of the current waveform. +/* DESC +This function aborts the transmission of the current waveform. - Returns 0 if OK. +Returns 0 if OK. - NOTES: - - This function is intended to stop a waveform started in repeat mode. -*/ +This function is intended to stop a waveform started in repeat mode. +DESC */ -/*-------------------------------------------------------------------------*/ +/* FUNC */ int gpioWaveGetMicros(void); -/*-------------------------------------------------------------------------*/ -/* This function returns the length in microseconds of the current - waveform. -*/ +/* DESC +This function returns the length in microseconds of the current +waveform. +DESC */ -/*-------------------------------------------------------------------------*/ +/* FUNC */ int gpioWaveGetHighMicros(void); -/*-------------------------------------------------------------------------*/ -/* This function returns the length in microseconds of the longest waveform - created since gpioInitialise was called. -*/ +/* DESC +This function returns the length in microseconds of the longest waveform +created since gpioInitialise was called. +DESC */ -/*-------------------------------------------------------------------------*/ +/* FUNC */ int gpioWaveGetMaxMicros(void); -/*-------------------------------------------------------------------------*/ -/* This function returns the maximum possible size of a waveform in - microseconds. -*/ +/* DESC +This function returns the maximum possible size of a waveform in +microseconds. +DESC */ -/*-------------------------------------------------------------------------*/ +/* FUNC */ int gpioWaveGetPulses(void); -/*-------------------------------------------------------------------------*/ -/* This function returns the length in pulses of the current waveform. -*/ +/* DESC +This function returns the length in pulses of the current waveform. +DESC */ -/*-------------------------------------------------------------------------*/ +/* FUNC */ int gpioWaveGetHighPulses(void); -/*-------------------------------------------------------------------------*/ -/* This function returns the length in pulses of the longest waveform - created since gpioInitialise was called. -*/ +/* DESC +This function returns the length in pulses of the longest waveform +created since gpioInitialise was called. +DESC */ -/*-------------------------------------------------------------------------*/ +/* FUNC */ int gpioWaveGetMaxPulses(void); -/*-------------------------------------------------------------------------*/ -/* This function returns the maximum possible size of a waveform in pulses. -*/ +/* DESC +This function returns the maximum possible size of a waveform in pulses. +DESC */ -/*-------------------------------------------------------------------------*/ +/* FUNC */ int gpioWaveGetCbs(void); -/*-------------------------------------------------------------------------*/ -/* This function returns the length in DMA control blocks of the current - waveform. -*/ +/* DESC +This function returns the length in DMA control blocks of the current +waveform. +DESC */ -/*-------------------------------------------------------------------------*/ +/* FUNC */ int gpioWaveGetHighCbs(void); -/*-------------------------------------------------------------------------*/ -/* This function returns the length in DMA control blocks of the longest - waveform created since gpioInitialise was called. -*/ +/* DESC +This function returns the length in DMA control blocks of the longest +waveform created since gpioInitialise was called. +DESC */ -/*-------------------------------------------------------------------------*/ +/* FUNC */ int gpioWaveGetMaxCbs(void); -/*-------------------------------------------------------------------------*/ -/* This function returns the maximum possible size of a waveform in DMA - control blocks. -*/ +/* DESC +This function returns the maximum possible size of a waveform in DMA +control blocks. +DESC */ -/*-------------------------------------------------------------------------*/ -int gpioSerialReadOpen(unsigned user_gpio, unsigned baud); -/*-------------------------------------------------------------------------*/ -/* This function opens a gpio for reading serial data. +/* FUNC */ +int gpioSerialReadOpen(unsigned user_gpio, unsigned bbBaud); +/* DESC +This function opens a gpio for reading serial data. - Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_WAVE_BAUD, - or PI_GPIO_IN_USE. +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_WAVE_BAUD, +or PI_GPIO_IN_USE. - The serial data is returned in a cyclic buffer and is read using - gpioSerialRead(). +The serial data is returned in a cyclic buffer and is read using +gpioSerialRead(). - It is the caller's responsibility to read data from the cyclic buffer - in a timely fashion. -*/ +It is the caller's responsibility to read data from the cyclic buffer +in a timely fashion. +DESC */ -/*-------------------------------------------------------------------------*/ +/* FUNC */ int gpioSerialRead(unsigned user_gpio, void *buf, size_t bufSize); -/*-------------------------------------------------------------------------*/ -/* This function copies up to bufSize bytes of data read from the - serial cyclic buffer to the buffer starting at buf. +/* DESC +This function copies up to bufSize bytes of data read from the +serial cyclic buffer to the buffer starting at buf. - Returns the number of bytes copied if OK, otherwise PI_BAD_USER_GPIO - or PI_NOT_SERIAL_GPIO. -*/ +Returns the number of bytes copied if OK, otherwise PI_BAD_USER_GPIO +or PI_NOT_SERIAL_GPIO. +DESC */ -/*-------------------------------------------------------------------------*/ +/* FUNC */ int gpioSerialReadClose(unsigned user_gpio); -/*-------------------------------------------------------------------------*/ -/* This function closes a gpio for reading serial data. +/* DESC +This function closes a gpio for reading serial data. - Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_NOT_SERIAL_GPIO. -*/ +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_NOT_SERIAL_GPIO. +DESC */ + +#define PI_I2C_SLOTS 32 +#define PI_SPI_SLOTS 4 +#define PI_SER_SLOTS 4 +#define PI_NUM_I2C_BUS 2 +#define PI_NUM_SPI_CHANNEL 2 -/*-------------------------------------------------------------------------*/ +#define PI_MAX_I2C_DEVICE_COUNT 1024 +#define PI_MAX_SPI_DEVICE_COUNT 1024 + + +/* FUNC */ +int i2cOpen(unsigned i2cBus, unsigned i2cAddr, unsigned i2cFlags); +/* DESC +This returns a handle for the device at the address on the I2C bus. + +No flags are currently defined. This parameter should be set to zero. + +Returns a handle (>=0) if OK, otherwise PI_BAD_I2C_BUS, PI_BAD_I2C_ADDR, +PI_BAD_FLAGS, PI_NO_HANDLE, or PI_I2C_OPEN_FAILED. +DESC */ + +/* FUNC */ +int i2cClose(unsigned handle); +/* DESC +This closes the I2C device associated with the handle. + +Returns 0 if OK, otherwise PI_BAD_HANDLE. +DESC */ + +/* FUNC */ +int i2cReadDevice(unsigned handle, char *buf, unsigned count); +/* DESC +This reads count bytes from the raw device into buf. + +Returns count (>0) if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_READ_FAILED. +DESC */ + +/* FUNC */ +int i2cWriteDevice(unsigned handle, char *buf, unsigned count); +/* DESC +This writes count bytes from buf to the raw device. + +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_WRITE_FAILED. +DESC */ + +/* FUNC */ +int i2cWriteQuick(unsigned handle, unsigned bit); +/* DESC +Sends a single bit to the device associated with handle +(smbus 2.0 5.5.1: Quick command). + +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_WRITE_FAILED. +DESC */ + +/* FUNC */ +int i2cWriteByte(unsigned handle, unsigned bVal); +/* DESC +Sends a single byte to the device associated with handle +(smbus 2.0 5.5.2: Send byte). + +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_WRITE_FAILED. +DESC */ + +/* FUNC */ +int i2cReadByte(unsigned handle); +/* DESC +Reads a single byte from the device associated with handle +(smbus 2.0 5.5.3: Receive byte). + +Returns the byte read (>=0) if OK, otherwise PI_BAD_HANDLE, +or PI_I2C_READ_FAILED. +DESC */ + +/* FUNC */ +int i2cWriteByteData(unsigned handle, unsigned reg, unsigned bVal); +/* DESC +Writes a single byte to the specified register of the device +associated with handle (smbus 2.0 5.5.4: Write byte). + +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_WRITE_FAILED. +DESC */ + +/* FUNC */ +int i2cWriteWordData(unsigned handle, unsigned reg, unsigned wVal); +/* DESC +Writes a single 16 bit word to the specified register of the device +associated with handle (smbus 2.0 5.5.4: Write word). + +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_WRITE_FAILED. +DESC */ + +/* FUNC */ +int i2cReadByteData(unsigned handle, unsigned reg); +/* DESC +Reads a single byte from the specified register of the device +associated with handle (smbus 2.0 5.5.5: Read byte). + +Returns the byte read (>=0) if OK, otherwise PI_BAD_HANDLE, +PI_BAD_PARAM, or PI_I2C_READ_FAILED. +DESC */ + +/* FUNC */ +int i2cReadWordData(unsigned handle, unsigned reg); +/* DESC +Reads a single 16 bit word from the specified register of the device +associated with handle (smbus 2.0 5.5.5: Read word). + +Returns the word read (>=0) if OK, otherwise PI_BAD_HANDLE, +PI_BAD_PARAM, or PI_I2C_READ_FAILED. +DESC */ + +/* FUNC */ +int i2cProcessCall(unsigned handle, unsigned reg, unsigned wVal); +/* DESC +Writes 16 bits of data to the specified register of the device +associated with handle and and reads 16 bits of data in return +(smbus 2.0 5.5.6: Process call). + +Returns the word read (>=0) if OK, otherwise PI_BAD_HANDLE, +PI_BAD_PARAM, or PI_I2C_READ_FAILED. +DESC */ + +/* FUNC */ +int i2cWriteBlockData( +unsigned handle, unsigned reg, char *buf, unsigned count); +/* DESC +Writes up to 32 bytes to the specified register of the device +associated with handle (smbus 2.0 5.5.7: Block write). + +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_WRITE_FAILED. +DESC */ + +/* FUNC */ +int i2cReadBlockData(unsigned handle, unsigned reg, char *buf); +/* DESC +Reads a block of up to 32 bytes from the specified register of +the device associated with handle (smbus 2.0 5.5.7: Block read). + +The amount of returned data is set by the device. + +Returns the number of bytes read (>=0) if OK, otherwise PI_BAD_HANDLE, +PI_BAD_PARAM, or PI_I2C_READ_FAILED. +DESC */ + +/* FUNC */ +int i2cBlockProcessCall( +unsigned handle, unsigned reg, char *buf, unsigned count); +/* DESC +Writes data bytes to the specified register of the device +associated with handle and reads a device specified number +of bytes of data in return (smbus 2.0 5.5.8: +Block write-block read). + +Returns the number of bytes read (>=0) if OK, otherwise PI_BAD_HANDLE, +PI_BAD_PARAM, or PI_I2C_READ_FAILED. + +The smbus 2.0 documentation states that a minimum of 1 byte may be +sent and a minimum of 1 byte may be received. The total number of +bytes sent/received must be 32 or less. +DESC */ + + +/* FUNC */ +int i2cReadI2CBlockData( +unsigned handle, unsigned reg, char *buf, unsigned count); +/* DESC +Reads count bytes from the specified register of the device +associated with handle . The count may be 1-32. + +Returns the number of bytes read (>=0) if OK, otherwise PI_BAD_HANDLE, +PI_BAD_PARAM, or PI_I2C_READ_FAILED. +DESC */ + + +/* FUNC */ +int i2cWriteI2CBlockData( +unsigned handle, unsigned reg, char *buf, unsigned count); +/* DESC +Writes data bytes to the specified register of the device +associated with handle . 1-32 bytes may be written. + +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_I2C_WRITE_FAILED. +DESC */ + +/* FUNC */ +int spiOpen(unsigned spiChan, unsigned spiBaud, unsigned spiFlags); +/* DESC +This function returns a handle for the SPI device on the channel +Data will be transferred at baud bits per second. + +The least significant two bits of flags define the SPI mode. + +. . +Mode POL PHA + 0 0 0 + 1 0 1 + 2 1 0 + 3 1 1 +. . + +The other bits in flags should be set to zero. + +Returns a handle (>=0) if OK, otherwise PI_BAD_SPI_CHANNEL, +PI_BAD_SPI_SPEED, PI_BAD_FLAGS, or PI_SPI_OPEN_FAILED. +DESC */ + +/* FUNC */ +int spiClose(unsigned handle); +/* DESC +This functions closes the SPI device identified by the handle. + +Returns 0 if OK, otherwise PI_BAD_HANDLE. +DESC */ + +/* FUNC */ +int spiRead(unsigned handle, char *buf, unsigned count); +/* DESC +This function reads count bytes of data from the SPI +device associated with the handle. + +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_SPI_COUNT, or +PI_SPI_XFER_FAILED. +DESC */ + +/* FUNC */ +int spiWrite(unsigned handle, char *buf, unsigned count); +/* DESC +This function writes count bytes of data from buf to the SPI +device associated with the handle. + +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_SPI_COUNT, or +PI_SPI_XFER_FAILED. +DESC */ + +/* FUNC */ +int spiXfer(unsigned handle, char *txBuf, char *rxBuf, unsigned count); +/* DESC +This function transfers count bytes of data from txBuf to the SPI +device associated with the handle. + +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_SPI_COUNT, or +PI_SPI_XFER_FAILED. + +The data read from the device is written to rxBuf. +DESC */ + +/* FUNC */ +int serOpen(char *tty, unsigned serBaud, unsigned serFlags); +/* DESC +This function open the serial device named tty at baud +bits per second. + +No flags are currently defined. This parameter should be set to zero. + +Returns a handle (>=0) if OK, otherwise PI_NO_HANDLE, or +PI_SER_OPEN_FAILED. +DESC */ + +/* FUNC */ +int serClose(unsigned handle); +/* DESC +This function closes the serial device associated with handle. + +Returns 0 if OK, otherwise PI_BAD_HANDLE. +DESC */ + +/* FUNC */ +int serWriteByte(unsigned handle, unsigned bVal); +/* DESC +This function writes bVal to the serial port associated with handle. + +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_SER_WRITE_FAILED. +DESC */ + +/* FUNC */ +int serReadByte(unsigned handle); +/* DESC +This function reads a byte from the serial port associated with handle. + +Returns the read byte (>=0) if OK, otherwise PI_BAD_HANDLE, +PI_SER_READ_NO_DATA, or PI_SER_READ_FAILED. +DESC */ + +/* FUNC */ +int serWrite(unsigned handle, char *buf, unsigned count); +/* DESC +This function writes count bytes from buf to the the serial port +associated with handle. + +Returns 0 if OK, otherwise PI_BAD_HANDLE, PI_BAD_PARAM, or +PI_SER_WRITE_FAILED. +DESC */ + +/* FUNC */ +int serRead(unsigned handle, char *buf, unsigned count); +/* DESC +This function reads count bytes from the the serial port +associated with handle and writes them to buf. + +Returns the number of bytes read (>0) if OK, otherwise PI_BAD_HANDLE, +PI_BAD_PARAM, PI_SER_READ_NO_DATA, or PI_SER_WRITE_FAILED. +DESC */ + +/* FUNC */ +int serDataAvailable(unsigned handle); +/* DESC +This function returns the number of bytes of serial data available +to be read from the serial device associated with handle. + +Returns the number of bytes of data available (>=0) if OK, +otherwise PI_BAD_HANDLE. +DESC */ + + +/* FUNC */ int gpioTrigger(unsigned user_gpio, unsigned pulseLen, unsigned level); -/*-------------------------------------------------------------------------*/ -/* This function sends a trigger pulse to a gpio. The gpio is set to - level for pulseLen microseconds and then reset to not level. +/* DESC +This function sends a trigger pulse to a gpio. The gpio is set to +level for pulseLen microseconds and then reset to not level. - Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_LEVEL, - or PI_BAD_PULSELEN. -*/ +Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_LEVEL, +or PI_BAD_PULSELEN. +DESC */ #define PI_MAX_PULSELEN 50 -/*-------------------------------------------------------------------------*/ -int gpioSetWatchdog(unsigned user_gpio, - unsigned timeout); -/*-------------------------------------------------------------------------*/ -/* Sets a watchdog for a gpio. +/* FUNC */ +int gpioSetWatchdog(unsigned user_gpio, unsigned timeout); +/* DESC +Sets a watchdog for a gpio. - Returns 0 if OK, otherwise PI_BAD_USER_GPIO or PI_BAD_WDOG_TIMEOUT. - - The watchdog is nominally in milliseconds. +Returns 0 if OK, otherwise PI_BAD_USER_GPIO or PI_BAD_WDOG_TIMEOUT. - One watchdog may be registered per gpio. +The watchdog is nominally in milliseconds. - The watchdog may be cancelled by setting timeout to 0. +One watchdog may be registered per gpio. - If no level change has been detected for the gpio for timeout - milliseconds:- +The watchdog may be cancelled by setting timeout to 0. - 1) any registered alert function for the gpio is called with - the level set to PI_TIMEOUT. - 2) any notification for the gpio has a report written to the - fifo with the flags set to indicate a watchdog timeout. +If no level change has been detected for the gpio for timeout +milliseconds:- - EXAMPLE: +1) any registered alert function for the gpio is called with + the level set to PI_TIMEOUT. +2) any notification for the gpio has a report written to the + fifo with the flags set to indicate a watchdog timeout. - void aFunction(int gpio, int level, uint32_t tick) - { - printf("gpio %d became %d at %d\n", gpio, level, tick); - } - ... - gpioSetAlertFunc(4, aFunction); - gpioSetWatchdogTimeout(4, 5); - ... +... +void aFunction(int gpio, int level, uint32_t tick) +{ + printf("gpio %d became %d at %d\n", gpio, level, tick); +} - This example causes aFunction to be called whenever - gpio 4 changes state or approximately every 5 ms. -*/ +// call aFunction whenever gpio 4 changes state +gpioSetAlertFunc(4, aFunction); + +// or approximately every 5 millis +gpioSetWatchdogTimeout(4, 5); +... + +DESC */ /* timeout: 0-60000 */ @@ -1261,185 +1599,174 @@ int gpioSetWatchdog(unsigned user_gpio, -/*-------------------------------------------------------------------------*/ -int gpioSetGetSamplesFunc(gpioGetSamplesFunc_t f, - uint32_t bits); -/*-------------------------------------------------------------------------*/ -/* Registers a function to be called (a callback) every millisecond - with the latest gpio samples. +/* FUNC */ +int gpioSetGetSamplesFunc(gpioGetSamplesFunc_t f, uint32_t bits); +/* DESC +Registers a function to be called (a callback) every millisecond +with the latest gpio samples. - Returns 0 if OK. +Returns 0 if OK. - The function is passed a pointer to the samples and the number - of samples. +The function is passed a pointer to the samples and the number +of samples. - Only one function can be registered. +Only one function can be registered. - The callback may be cancelled by passing NULL as the function. +The callback may be cancelled by passing NULL as the function. - NOTES: +The samples returned will be the union of bits, plus any active alerts, +plus any active notifications. - The samples returned will be the union of bits, plus any active alerts, - plus any active notifications. - - e.g. if there are alerts for gpios 7, 8, and 9, notifications for gpios - 8, 10, 23, 24, and bits is (1<<23)|(1<<17) then samples for gpios - 7, 8, 9, 10, 17, 23, and 24 will be reported. -*/ +e.g. if there are alerts for gpios 7, 8, and 9, notifications for gpios +8, 10, 23, 24, and bits is (1<<23)|(1<<17) then samples for gpios +7, 8, 9, 10, 17, 23, and 24 will be reported. +DESC */ -/*-------------------------------------------------------------------------*/ -int gpioSetGetSamplesFuncEx(gpioGetSamplesFuncEx_t f, - uint32_t bits, - void * userdata); -/*-------------------------------------------------------------------------*/ -/* Registers a function to be called (a callback) every millisecond - with the latest gpio samples. +/* FUNC */ +int gpioSetGetSamplesFuncEx( + gpioGetSamplesFuncEx_t f, uint32_t bits, void *userdata); +/* DESC +Registers a function to be called (a callback) every millisecond +with the latest gpio samples. - Returns 0 if OK. +Returns 0 if OK. - The function is passed a pointer to the samples, the number - of samples, and the userdata pointer. +The function is passed a pointer to the samples, the number +of samples, and the userdata pointer. - Only one of gpioGetSamplesFunc or gpioGetSamplesFuncEx can be - registered. +Only one of gpioGetSamplesFunc or gpioGetSamplesFuncEx can be +registered. - See gpioSetGetSamplesFunc for further details. -*/ +See gpioSetGetSamplesFunc for further details. +DESC */ -/*-------------------------------------------------------------------------*/ -int gpioSetTimerFunc(unsigned timer, - unsigned ms, - gpioTimerFunc_t f); -/*-------------------------------------------------------------------------*/ -/* Registers a function to be called (a callback) every ms milliseconds. +/* FUNC */ +int gpioSetTimerFunc(unsigned timer, unsigned millis, gpioTimerFunc_t f); +/* DESC +Registers a function to be called (a callback) every millis milliseconds. - Returns 0 if OK, otherwise PI_BAD_TIMER, PI_BAD_MS, or PI_TIMER_FAILED. +Returns 0 if OK, otherwise PI_BAD_TIMER, PI_BAD_MS, or PI_TIMER_FAILED. - 10 timers are supported numbered 0 to 9. +10 timers are supported numbered 0 to 9. - One function may be registered per timer. +One function may be registered per timer. - The timer may be cancelled by passing NULL as the function. +The timer may be cancelled by passing NULL as the function. - EXAMPLE: +... +void bFunction(void) +{ + printf("two seconds have elapsed\n"); +} - ... - void bFunction(void) - { - printf("two seconds have elapsed\n"); - } - ... - gpioSetTimerFunc(0, 2000, bFunction); - ... - - This example causes bFunction to be called every 2000 milliseconds. -*/ +// call bFunction every 2000 milliseconds +gpioSetTimerFunc(0, 2000, bFunction); +... +DESC */ /* timer: 0-9 */ #define PI_MIN_TIMER 0 #define PI_MAX_TIMER 9 -/* ms: 10-60000 */ +/* millis: 10-60000 */ #define PI_MIN_MS 10 #define PI_MAX_MS 60000 -/*-------------------------------------------------------------------------*/ -int gpioSetTimerFuncEx(unsigned timer, - unsigned ms, - gpioTimerFuncEx_t f, - void * userdata); -/*-------------------------------------------------------------------------*/ -/* Registers a function to be called (a callback) every ms milliseconds. +/* FUNC */ +int gpioSetTimerFuncEx( + unsigned timer, unsigned millis, gpioTimerFuncEx_t f, void *userdata); +/* DESC +Registers a function to be called (a callback) every millis milliseconds. - Returns 0 if OK, otherwise PI_BAD_TIMER, PI_BAD_MS, or PI_TIMER_FAILED. +Returns 0 if OK, otherwise PI_BAD_TIMER, PI_BAD_MS, or PI_TIMER_FAILED. - The function is passed the userdata pointer. +The function is passed the userdata pointer. - Only one of gpioSetTimerFunc or gpioSetTimerFuncEx can be - registered per timer. +Only one of gpioSetTimerFunc or gpioSetTimerFuncEx can be +registered per timer. - See gpioSetTimerFunc for further details. -*/ +See gpioSetTimerFunc for further details. +DESC */ -/* ----------------------------------------------------------------------- */ -pthread_t *gpioStartThread(gpioThreadFunc_t func, void *arg); -/*-------------------------------------------------------------------------*/ -/* Starts a new thread of execution with func as the main routine. +/* FUNC */ +pthread_t *gpioStartThread(gpioThreadFunc_t f, void *arg); +/* DESC +Starts a new thread of execution with f as the main routine. - Returns a pointer to pthread_t if OK, otherwise NULL. +Returns a pointer to pthread_t if OK, otherwise NULL. - The function is passed the single argument arg. +The function is passed the single argument arg. - The thread can be cancelled by passing the pointer to pthread_t to - gpioStopThread(). +The thread can be cancelled by passing the pointer to pthread_t to +gpioStopThread(). - EXAMPLE: +... +#include +#include - #include - #include - - void *myfunc(void *arg) +void *myfunc(void *arg) +{ + while (1) { - while (1) - { - printf("%s\n", arg); - sleep(1); - } + printf("%s\n", arg); + sleep(1); } +} - int main(int argc, char *argv[]) - { - pthread_t *p1, *p2, *p3; +int main(int argc, char *argv[]) +{ + pthread_t *p1, *p2, *p3; - if (gpioInitialise() < 0) return 1; + if (gpioInitialise() < 0) return 1; - p1 = gpioStartThread(myfunc, "thread 1"); sleep(3); + p1 = gpioStartThread(myfunc, "thread 1"); sleep(3); - p2 = gpioStartThread(myfunc, "thread 2"); sleep(3); + p2 = gpioStartThread(myfunc, "thread 2"); sleep(3); - p3 = gpioStartThread(myfunc, "thread 3"); sleep(3); + p3 = gpioStartThread(myfunc, "thread 3"); sleep(3); - gpioStopThread(p3); sleep(3); + gpioStopThread(p3); sleep(3); - gpioStopThread(p2); sleep(3); + gpioStopThread(p2); sleep(3); - gpioStopThread(p1); sleep(3); + gpioStopThread(p1); sleep(3); - gpioTerminate(); - } -*/ + gpioTerminate(); +} +... +DESC */ -/* ----------------------------------------------------------------------- */ +/* FUNC */ void gpioStopThread(pthread_t *pth); -/*-------------------------------------------------------------------------*/ -/* Cancels the thread pointed at by pth. +/* DESC +Cancels the thread pointed at by pth. - No value is returned. +No value is returned. - The thread to be stopped should have been started with gpioStartThread(). -*/ +The thread to be stopped should have been started with gpioStartThread(). +DESC */ -/* ----------------------------------------------------------------------- */ +/* FUNC */ int gpioStoreScript(char *script); -/* ----------------------------------------------------------------------- */ -/* This function stores a null terminated script for later execution. +/* DESC +This function stores a null terminated script for later execution. - The function returns a script id if the script is valid, - otherwise PI_BAD_SCRIPT. -*/ +The function returns a script id if the script is valid, +otherwise PI_BAD_SCRIPT. +DESC */ #define PI_MAX_SCRIPTS 32 @@ -1448,38 +1775,38 @@ int gpioStoreScript(char *script); #define PI_MAX_SCRIPT_PARAMS 10 -/* ----------------------------------------------------------------------- */ +/* FUNC */ int gpioRunScript(unsigned script_id, unsigned numParam, uint32_t *param); -/* ----------------------------------------------------------------------- */ -/* This function runs a stored script. +/* DESC +This function runs a stored script. - The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID, or - PI_TOO_MANY_PARAM. +The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID, or +PI_TOO_MANY_PARAM. - param is an array of up to 10 parameters which may be referenced in - the script as param 0 to param 9. -*/ +param is an array of up to 10 parameters which may be referenced in +the script as param 0 to param 9. +DESC */ -/* ----------------------------------------------------------------------- */ +/* FUNC */ int gpioScriptStatus(unsigned script_id, uint32_t *param); -/* ----------------------------------------------------------------------- */ -/* This function returns the run status of a stored script as well as - the current values of parameters 0 to 9. +/* DESC +This function returns the run status of a stored script as well as +the current values of parameters 0 to 9. - The function returns greater than or equal to 0 if OK, - otherwise PI_BAD_SCRIPT_ID. +The function returns greater than or equal to 0 if OK, +otherwise PI_BAD_SCRIPT_ID. - The run status may be +The run status may be - PI_SCRIPT_HALTED - PI_SCRIPT_RUNNING - PI_SCRIPT_WAITING - PI_SCRIPT_FAILED +PI_SCRIPT_HALTED +PI_SCRIPT_RUNNING +PI_SCRIPT_WAITING +PI_SCRIPT_FAILED - The current value of script parameters 0 to 9 are returned in param. -*/ +The current value of script parameters 0 to 9 are returned in param. +DESC */ /* script status */ @@ -1490,45 +1817,42 @@ int gpioScriptStatus(unsigned script_id, uint32_t *param); -/* ----------------------------------------------------------------------- */ +/* FUNC */ int gpioStopScript(unsigned script_id); -/* ----------------------------------------------------------------------- */ -/* This function stops a running script. +/* DESC +This function stops a running script. - The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID. -*/ +The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID. +DESC */ -/* ----------------------------------------------------------------------- */ +/* FUNC */ int gpioDeleteScript(unsigned script_id); -/* ----------------------------------------------------------------------- */ -/* This function deletes a stored script. +/* DESC +This function deletes a stored script. - The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID. -*/ +The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID. +DESC */ -/*-------------------------------------------------------------------------*/ -int gpioSetSignalFunc(unsigned signum, - gpioSignalFunc_t f); -/*-------------------------------------------------------------------------*/ -/* Registers a function to be called (a callback) when a signal occurs. +/* FUNC */ +int gpioSetSignalFunc(unsigned signum, gpioSignalFunc_t f); +/* DESC +Registers a function to be called (a callback) when a signal occurs. - Returns 0 if OK, otherwise PI_BAD_SIGNUM. +Returns 0 if OK, otherwise PI_BAD_SIGNUM. - The function is passed the signal number. +The function is passed the signal number. - One function may be registered per signal. +One function may be registered per signal. - The callback may be cancelled by passing NULL. +The callback may be cancelled by passing NULL. - NOTES: - - By default all signals are treated as fatal and cause the library - to call gpioTerminate and then exit. -*/ +By default all signals are treated as fatal and cause the library +to call gpioTerminate and then exit. +DESC */ /* signum: 0-63 */ @@ -1537,124 +1861,110 @@ int gpioSetSignalFunc(unsigned signum, -/*-------------------------------------------------------------------------*/ -int gpioSetSignalFuncEx(unsigned signum, - gpioSignalFuncEx_t f, - void * userdata); -/*-------------------------------------------------------------------------*/ -/* Registers a function to be called (a callback) when a signal occurs. +/* FUNC */ +int gpioSetSignalFuncEx( + unsigned signum, gpioSignalFuncEx_t f, void *userdata); +/* DESC +Registers a function to be called (a callback) when a signal occurs. - Returns 0 if OK, otherwise PI_BAD_SIGNUM. +Returns 0 if OK, otherwise PI_BAD_SIGNUM. - The function is passed the signal number and the userdata pointer. +The function is passed the signal number and the userdata pointer. - Only one of gpioSetSignalFunc or gpioSetSignalFuncEx can be - registered per signal. +Only one of gpioSetSignalFunc or gpioSetSignalFuncEx can be +registered per signal. - See gpioSetSignalFunc for further details. -*/ +See gpioSetSignalFunc for further details. +DESC */ -/*-------------------------------------------------------------------------*/ +/* FUNC */ uint32_t gpioRead_Bits_0_31(void); -/*-------------------------------------------------------------------------*/ -/* Returns the current level of gpios 0-31. -*/ +/* DESC +Returns the current level of gpios 0-31. +DESC */ -/*-------------------------------------------------------------------------*/ +/* FUNC */ uint32_t gpioRead_Bits_32_53(void); -/*-------------------------------------------------------------------------*/ -/* Returns the current level of gpios 32-53. -*/ +/* DESC +Returns the current level of gpios 32-53. +DESC */ -/*-------------------------------------------------------------------------*/ -int gpioWrite_Bits_0_31_Clear(uint32_t levels); -/*-------------------------------------------------------------------------*/ -/* Clears gpios 0-31 if the corresponding bit in levels is set. +/* FUNC */ +int gpioWrite_Bits_0_31_Clear(uint32_t bits); +/* DESC +Clears gpios 0-31 if the corresponding bit in bits is set. - Returns 0 if OK. +Returns 0 if OK. - EXAMPLE: - - To clear (set to 0) gpios 4, 7, and 15. - - ... - gpioWrite_Bits_0_31_Clear( (1<<4) | (1<<7) | (1<<15) ); - ... -*/ +... +// To clear (set to 0) gpios 4, 7, and 15 +gpioWrite_Bits_0_31_Clear( (1<<4) | (1<<7) | (1<<15) ); +... +DESC */ -/*-------------------------------------------------------------------------*/ -int gpioWrite_Bits_32_53_Clear(uint32_t levels); -/*-------------------------------------------------------------------------*/ -/* Clears gpios 32-53 if the corresponding bit (0-21) in levels is set. +/* FUNC */ +int gpioWrite_Bits_32_53_Clear(uint32_t bits); +/* DESC +Clears gpios 32-53 if the corresponding bit (0-21) in bits is set. - Returns 0 if OK. -*/ +Returns 0 if OK. +DESC */ -/*-------------------------------------------------------------------------*/ -int gpioWrite_Bits_0_31_Set(uint32_t levels); -/*-------------------------------------------------------------------------*/ -/* Sets gpios 0-31 if the corresponding bit in levels is set. +/* FUNC */ +int gpioWrite_Bits_0_31_Set(uint32_t bits); +/* DESC +Sets gpios 0-31 if the corresponding bit in bits is set. - Returns 0 if OK. -*/ +Returns 0 if OK. +DESC */ -/*-------------------------------------------------------------------------*/ -int gpioWrite_Bits_32_53_Set(uint32_t levels); -/*-------------------------------------------------------------------------*/ -/* Sets gpios 32-53 if the corresponding bit (0-21) in levels is set. +/* FUNC */ +int gpioWrite_Bits_32_53_Set(uint32_t bits); +/* DESC +Sets gpios 32-53 if the corresponding bit (0-21) in bits is set. - Returns 0 if OK. +Returns 0 if OK. - EXAMPLE: - - To set (set to 1) gpios 32, 40, and 53. - - ... - gpioWrite_Bits_32_53_Set( (1<<(32-32)) | (1<<(40-32)) | (1<<(53-32)) ); - ... -*/ - -/*-------------------------------------------------------------------------*/ +... +// To set (set to 1) gpios 32, 40, and 53 +gpioWrite_Bits_32_53_Set( (1<<(32-32)) | (1<<(40-32)) | (1<<(53-32)) ); +... +DESC */ +/* FUNC */ +int gpioTime(unsigned timetype, int *seconds, int *micros); +/* DESC +Updates the seconds and micros variables with the current time. -/*-------------------------------------------------------------------------*/ -int gpioTime(unsigned timetype, - int * seconds, - int * micros); -/*-------------------------------------------------------------------------*/ -/* Updates the seconds and micros variables with the current time. +Returns 0 if OK, otherwise PI_BAD_TIMETYPE. - Returns 0 if OK, otherwise PI_BAD_TIMETYPE. +If timetype is PI_TIME_ABSOLUTE updates seconds and micros with the +number of seconds and microseconds since the epoch (1st January 1970). - If timetype is PI_TIME_ABSOLUTE updates seconds and micros with the - number of seconds and microseconds since the epoch (1st January 1970). +If timetype is PI_TIME_RELATIVE updates seconds and micros with the +number of seconds and microseconds since the library was initialised. - If timetype is PI_TIME_RELATIVE updates seconds and micros with the - number of seconds and microseconds since the library was initialised. +... +int secs, mics; - EXAMPLE: - - ... - int secs, mics; - ... - gpioTime(PI_TIME_RELATIVE, &secs, &mics); - printf("library started %d.%03d seconds ago\n", secs, mics/1000); - ... - prints the number of seconds since the library was started. -*/ +// print the number of seconds since the library was started +gpioTime(PI_TIME_RELATIVE, &secs, &mics); +printf("library started %d.%03d seconds ago\n", secs, mics/1000); +... +DESC */ /* timetype: 0-1 */ @@ -1663,149 +1973,135 @@ int gpioTime(unsigned timetype, -/*-------------------------------------------------------------------------*/ -int gpioSleep(unsigned timetype, - int seconds, - int micros); -/*-------------------------------------------------------------------------*/ -/* Sleeps for the number of seconds and microseconds specified by seconds - and micros. +/* FUNC */ +int gpioSleep(unsigned timetype, int seconds, int micros); +/* DESC +Sleeps for the number of seconds and microseconds specified by seconds +and micros. - Returns 0 if OK, otherwise PI_BAD_TIMETYPE, PI_BAD_SECONDS, - or PI_BAD_MICROS. - - If timetype is PI_TIME_ABSOLUTE the sleep ends when the number of seconds - and microseconds since the epoch (1st January 1970) has elapsed. System - clock changes are taken into account. +Returns 0 if OK, otherwise PI_BAD_TIMETYPE, PI_BAD_SECONDS, +or PI_BAD_MICROS. - If timetype is PI_TIME_RELATIVE the sleep is for the specified number - of seconds and microseconds. System clock changes do not effect the - sleep length. +If timetype is PI_TIME_ABSOLUTE the sleep ends when the number of seconds +and microseconds since the epoch (1st January 1970) has elapsed. System +clock changes are taken into account. - NOTES: +If timetype is PI_TIME_RELATIVE the sleep is for the specified number +of seconds and microseconds. System clock changes do not effect the +sleep length. - For short delays (say, 250 microseonds or less) use gpioDelayMicroseconds. +For short delays (say, 50 microseonds or less) use gpioDelayMicroseconds. - EXAMPLE: +... +gpioSleep(PI_TIME_RELATIVE, 2, 500000); // sleep for 2.5 seconds - ... - gpioSleep(PI_TIME_RELATIVE, 2, 500000); // sleep for 2.5 seconds - ... - gpioSleep(PI_TIME_RELATIVE, 0, 100000); // sleep for 1/10th of a second - ... - gpioSleep(PI_TIME_RELATIVE, 60, 0); // sleep for one minute - ... -*/ +gpioSleep(PI_TIME_RELATIVE, 0, 100000); // sleep for 1/10th of a second + +gpioSleep(PI_TIME_RELATIVE, 60, 0); // sleep for one minute +... +DESC */ -/*-------------------------------------------------------------------------*/ +/* FUNC */ uint32_t gpioDelay(uint32_t micros); -/*-------------------------------------------------------------------------*/ -/* Delays for at least the number of microseconds specified by micros. +/* DESC +Delays for at least the number of microseconds specified by micros. - Returns the actual length of the delay in microseconds. -*/ +Returns the actual length of the delay in microseconds. +DESC */ #define PI_MAX_MICS_DELAY 1000000 /* 1 second */ #define PI_MAX_MILS_DELAY 60000 /* 60 seconds */ -/*-------------------------------------------------------------------------*/ +/* FUNC */ uint32_t gpioTick(void); -/*-------------------------------------------------------------------------*/ -/* Returns the current system tick. +/* DESC +Returns the current system tick. - Tick is the number of microseconds since system boot. +Tick is the number of microseconds since system boot. - NOTES: +As tick is an unsigned 32 bit quantity it wraps around after +2^32 microseconds, which is approximately 1 hour 12 minutes. - As tick is an unsigned 32 bit quantity it wraps around after - 2^32 microseconds, which is approximately 1 hour 12 minutes. +You don't need to worry about the wrap around as long as you +take a tick (uint32_t) from another tick, i.e. the following +code will always provide the correct difference. - You don't need to worry about the wrap around as long as you - take a tick (uint32_t) from another tick, i.e. the following - code will always provide the correct difference. +... +uint32_t startTick, endTick; +int diffTick; - EXAMPLE: +startTick = gpioTick(); - uint32_t startTick, endTick; - int diffTick; - ... - startTick = gpioTick(); - ... - // do some processing - ... - endTick = gpioTick(); +// do some processing - diffTick = endTick - startTick; +endTick = gpioTick(); - printf("some processing took %d microseconds\n", diffTick); - ... -*/ +diffTick = endTick - startTick; + +printf("some processing took %d microseconds\n", diffTick); +... +DESC */ -/*-------------------------------------------------------------------------*/ +/* FUNC */ unsigned gpioHardwareRevision(void); -/*-------------------------------------------------------------------------*/ -/* Returns the hardware revision. +/* DESC +Returns the hardware revision. - If the hardware revision can not be found or is not a valid hexadecimal - number the function returns 0. +If the hardware revision can not be found or is not a valid hexadecimal +number the function returns 0. - NOTES: +The hardware revision is the last 4 characters on the Revision line of +/proc/cpuinfo. - The hardware revision is the last 4 characters on the Revision line of - /proc/cpuinfo. +The revision number can be used to determine the assignment of gpios +to pins. - The revision number can be used to determine the assignment of gpios - to pins. +There are at least two types of board. - There are at least two types of board. +Type 1 has gpio 0 on P1-3, gpio 1 on P1-5, and gpio 21 on P1-13. - Type 1 has gpio 0 on P1-3, gpio 1 on P1-5, and gpio 21 on P1-13. +Type 2 has gpio 2 on P1-3, gpio 3 on P1-5, gpio 27 on P1-13, and +gpios 28-31 on P5. - Type 2 has gpio 2 on P1-3, gpio 3 on P1-5, gpio 27 on P1-13, and - gpios 28-31 on P5. +Type 1 boards have hardware revision numbers of 2 and 3. - Type 1 boards have hardware revision numbers of 2 and 3. +Type 2 boards have hardware revision numbers of 4, 5, 6, and 15. - Type 2 boards have hardware revision numbers of 4, 5, 6, and 15. - - EXAMPLES: - - for "Revision : 0002" the function returns 2. - for "Revision : 000f" the function returns 15. - for "Revision : 000g" the function returns 0. -*/ +for "Revision : 0002" the function returns 2. +for "Revision : 000f" the function returns 15. +for "Revision : 000g" the function returns 0. +DESC */ -/*-------------------------------------------------------------------------*/ +/* FUNC */ unsigned gpioVersion(void); -/*-------------------------------------------------------------------------*/ -/* Returns the pigpio version. -*/ +/* DESC +Returns the pigpio version. +DESC */ -/*-------------------------------------------------------------------------*/ +/* FUNC */ int gpioCfgBufferSize(unsigned millis); -/*-------------------------------------------------------------------------*/ -/* Configures pigpio to buffer millis milliseconds of gpio samples. +/* DESC +Configures pigpio to buffer millis milliseconds of gpio samples. - The default setting is 120 milliseconds. +The default setting is 120 milliseconds. - NOTES: +The intention is to allow for bursts of data and protection against +other processes hogging cpu time. - The intention is to allow for bursts of data and protection against - other processes hogging cpu time. +I haven't seen a process locked out for more than 100 milliseconds. - I haven't seen a process locked out for more than 100 milliseconds. - - Making the buffer bigger uses a LOT of memory at the more frequent - sampling rates as shown in the following table in MBs. +Making the buffer bigger uses a LOT of memory at the more frequent +sampling rates as shown in the following table in MBs. +. . buffer milliseconds 120 250 500 1sec 2sec 4sec 8sec @@ -1815,7 +2111,8 @@ sample 4 8 12 18 31 55 107 --- rate 5 8 10 14 24 45 87 --- (us) 8 6 8 12 18 31 55 107 10 6 8 10 14 24 45 87 -*/ +. . +DESC */ /* millis */ @@ -1824,39 +2121,35 @@ sample 4 8 12 18 31 55 107 --- -/*-------------------------------------------------------------------------*/ -int gpioCfgClock(unsigned micros, - unsigned peripheral, - unsigned source); -/*-------------------------------------------------------------------------*/ -/* Configures pigpio to use a sample rate of micros microseconds, - permitted values are 1, 2, 4, 5, 8 and 10. +/* FUNC */ +int gpioCfgClock( + unsigned micros, unsigned peripheral, unsigned source); +/* DESC +Configures pigpio to use a sample rate of micros microseconds, +permitted values are 1, 2, 4, 5, 8 and 10. - The timings are provided by the specified peripheral (PWM or PCM) - using the frequency source (OSC or PLLD). +The timings are provided by the specified peripheral (PWM or PCM) +using the frequency source (OSC or PLLD). - The default setting is 5 microseconds using the PCM peripheral - with the PLLD source. +The default setting is 5 microseconds using the PCM peripheral +with the PLLD source. - NOTES: +The approximate CPU percentage used for each sample rate is: - The approximate CPU percentage used for each sample rate is: +. . +sample cpu + rate % - sample cpu - rate % + 1 25 + 2 16 + 4 11 + 5 10 + 8 15 + 10 14 +. . - 1 25 - 2 16 - 4 11 - 5 10 - 8 15 - 10 14 - - A sample rate of 5 microseconds seeems to be the sweet spot. - - These readings were done by checking the resources used by - the demolib program (which is reasonably busy). -*/ +A sample rate of 5 microseconds seeems to be the sweet spot. +DESC */ /* micros: 1, 2, 4, 5, 8, or 10 */ @@ -1872,61 +2165,70 @@ int gpioCfgClock(unsigned micros, -/*-------------------------------------------------------------------------*/ -int gpioCfgDMAchannel(unsigned channel); /* DEPRECATED */ -/*-------------------------------------------------------------------------*/ -/* Configures pigpio to use the specified DMA channel. +/* FUNC */ +int gpioCfgDMAchannel(unsigned DMAchannel); /* DEPRECATED */ +/* DESC +Configures pigpio to use the specified DMA channel. - The default setting is to use channel 14. -*/ +The default setting is to use channel 14. +DESC */ -/* channel: 0-14 */ +/* DMA channel: 0-14 */ #define PI_MIN_DMA_CHANNEL 0 #define PI_MAX_DMA_CHANNEL 14 -/*-------------------------------------------------------------------------*/ -int gpioCfgDMAchannels(unsigned primaryChannel, - unsigned secondaryChannel); -/*-------------------------------------------------------------------------*/ -/* Configures pigpio to use the specified DMA channels. +/* FUNC */ +int gpioCfgDMAchannels( + unsigned primaryChannel, unsigned secondaryChannel); +/* DESC +Configures pigpio to use the specified DMA channels. - The default setting is to use channel 14 for the primary channel and - channel 5 for the secondary channel. -*/ +The default setting is to use channel 14 for the primary channel and +channel 5 for the secondary channel. +DESC */ #define PI_MAX_PRIMARY_CHANNEL 14 #define PI_MAX_SECONDARY_CHANNEL 6 -/*-------------------------------------------------------------------------*/ +/* FUNC */ int gpioCfgPermissions(uint64_t updateMask); -/*-------------------------------------------------------------------------*/ -/* Configures pigpio to only allow updates (writes or mode changes) for the - gpios specified by the mask. +/* DESC +Configures pigpio to only allow updates (writes or mode changes) for the +gpios specified by the mask. - The default setting depends upon the board revision (Type 1 or Type 2). - The user gpios are added to the mask. If the board revision is not - recognised then the mask is formed by or'ing the bits for the two - board revisions. +The default setting depends upon the board revision (Type 1 or Type 2). +The user gpios are added to the mask. If the board revision is not +recognised then the mask is formed by or'ing the bits for the two +board revisions. - Unknown board: PI_DEFAULT_UPDATE_MASK_R0 0xFBE6CF9F - Type 1 board: PI_DEFAULT_UPDATE_MASK_R1 0x03E6CF93 - Type 2 board: PI_DEFAULT_UPDATE_MASK_R2 0xFBC6CF9C -*/ +Unknown board +. . +PI_DEFAULT_UPDATE_MASK_R0 0xFBE6CF9F +. . +Type 1 board +. . +PI_DEFAULT_UPDATE_MASK_R1 0x03E6CF93 +. . +Type 2 board +. . +PI_DEFAULT_UPDATE_MASK_R2 0xFBC6CF9C +. . +DESC */ -/*-------------------------------------------------------------------------*/ +/* FUNC */ int gpioCfgSocketPort(unsigned port); -/*-------------------------------------------------------------------------*/ -/* Configures pigpio to use the specified socket port. +/* DESC +Configures pigpio to use the specified socket port. - The default setting is to use port 8888. -*/ +The default setting is to use port 8888. +DESC */ /* port: 1024-9999 */ @@ -1935,181 +2237,564 @@ int gpioCfgSocketPort(unsigned port); -/*-------------------------------------------------------------------------*/ +/* FUNC */ int gpioCfgInterfaces(unsigned ifFlags); -/*-------------------------------------------------------------------------*/ -/* Configures pigpio support of the fifo and socket interfaces. +/* DESC +Configures pigpio support of the fifo and socket interfaces. - The default setting is that both interfaces are enabled. -*/ +The default setting is that both interfaces are enabled. +DESC */ /* ifFlags: */ #define PI_DISABLE_FIFO_IF 1 #define PI_DISABLE_SOCK_IF 2 -/*-------------------------------------------------------------------------*/ -int gpioCfgInternals(unsigned what, - int value); -/*-------------------------------------------------------------------------*/ -/* Used to tune internal settings. +/* FUNC */ +int gpioCfgInternals(unsigned cfgWhat, int cfgVal); +/* DESC +Used to tune internal settings. - Not intended for general use. -*/ +Not intended for general use. +DESC */ -/*-------------------------------------------------------------------------*/ +/* FUNC */ int rawWaveAddSPI( rawSPI_t *spi, unsigned offset, - unsigned ss, - uint8_t *tx_bits, - unsigned num_tx_bits, - unsigned rx_bit_first, - unsigned rx_bit_last, - unsigned bits); -/*-------------------------------------------------------------------------*/ -/* This function adds a waveform representing SPI data to the - existing waveform (if any). The SPI data starts offset microseconds - from the start of the waveform. ss is the slave select gpio. bits bits - are transferred. num_tx_bits are transmitted starting at the first bit. - The bits to transmit are read, most significant bit first, from tx_bits. - Gpio reads are made from rx_bit_first to rx_bit_last. + unsigned spiSS, + char *buf, + unsigned spiTxBits, + unsigned spiBitFirst, + unsigned spiBitLast, + unsigned spiBits); +/* DESC +This function adds a waveform representing SPI data to the +existing waveform (if any). - Returns the new total number of pulses in the current waveform if OK, - otherwise PI_BAD_USER_GPIO, PI_BAD_SER_OFFSET, or PI_TOO_MANY_PULSES. +The SPI data starts offset microseconds from the start of the +waveform. spiSS is the slave select gpio. spiBits bits +are transferred. spiTxBits are transmitted starting at the +first bit. The bits to transmit are read, most significant bit +first, from buf. Gpio reads are made from spiBitFirst to +spiBitLast. - Not intended for general use. -*/ +Returns the new total number of pulses in the current waveform if OK, +otherwise PI_BAD_USER_GPIO, PI_BAD_SER_OFFSET, or PI_TOO_MANY_PULSES. -/*-------------------------------------------------------------------------*/ +Not intended for general use. +DESC */ + +/* FUNC */ int rawWaveAddGeneric(unsigned numPulses, rawWave_t *pulses); -/*-------------------------------------------------------------------------*/ -/* This function adds a number of pulses to the current waveform. +/* DESC +This function adds a number of pulses to the current waveform. - Returns the new total number of pulses in the current waveform if OK, - otherwise PI_TOO_MANY_PULSES. +Returns the new total number of pulses in the current waveform if OK, +otherwise PI_TOO_MANY_PULSES. - NOTES: +The advantage of this function over gpioWaveAddGeneric is that it +allows the setting of the flags field. - The advantage of this function over gpioWaveAddGeneric is that it - allows the setting of the flags field. +The pulses are interleaved in time order within the existing waveform +(if any). - The pulses are interleaved in time order within the existing waveform - (if any). +Merging allows the waveform to be built in parts, that is the settings +for gpio#1 can be added, and then gpio#2 etc. - Merging allows the waveform to be built in parts, that is the settings - for gpio#1 can be added, and then gpio#2 etc. +If the added waveform is intended to start after or within the existing +waveform then the first pulse should consist of a delay. - If the added waveform is intended to start after or within the existing - waveform then the first pulse should consist of a delay. +Not intended for general use. +DESC */ - Not intended for general use. -*/ - - - -/* ----------------------------------------------------------------------- */ +/* FUNC */ unsigned rawWaveCB(void); -/* ----------------------------------------------------------------------- */ -/* - Returns the number of the cb being currently output. +/* DESC +Returns the number of the cb being currently output. - Not intended for general use. -*/ +Not intended for general use. +DESC */ -/* ----------------------------------------------------------------------- */ -rawCbs_t * rawWaveCBAdr(int n); -/* ----------------------------------------------------------------------- */ -/* - Return the Linux address of contol block n. +/* FUNC */ +rawCbs_t *rawWaveCBAdr(int n); +/* DESC +Return the Linux address of contol block n. - Not intended for general use. -*/ +Not intended for general use. +DESC */ -/* ----------------------------------------------------------------------- */ +/* FUNC */ uint32_t rawWaveGetOut(int pos); -/* ----------------------------------------------------------------------- */ -/* Gets the wave output parameter stored at pos. +/* DESC +Gets the wave output parameter stored at pos. - Not intended for general use. -*/ +Not intended for general use. +DESC */ -/* ----------------------------------------------------------------------- */ +/* FUNC */ void rawWaveSetOut(int pos, uint32_t value); -/* ----------------------------------------------------------------------- */ -/* Sets the wave output parameter stored at pos to value. +/* DESC +Sets the wave output parameter stored at pos to value. - Not intended for general use. -*/ +Not intended for general use. +DESC */ -/* ----------------------------------------------------------------------- */ +/* FUNC */ uint32_t rawWaveGetIn(int pos); -/* ----------------------------------------------------------------------- */ -/* Gets the wave input value parameter stored at pos. +/* DESC +Gets the wave input value parameter stored at pos. - Not intended for general use. -*/ +Not intended for general use. +DESC */ -/* ----------------------------------------------------------------------- */ +/* FUNC */ void rawWaveSetIn(int pos, uint32_t value); -/* ----------------------------------------------------------------------- */ -/* Sets the wave input value stored at pos to value. +/* DESC +Sets the wave input value stored at pos to value. - Not intended for general use. -*/ +Not intended for general use. +DESC */ -/*-------------------------------------------------------------------------*/ -int getBitInBytes(int bitPos, uint8_t *buf, int numBits); -/*-------------------------------------------------------------------------*/ -/* Returns the value of the bit bitPos bits from the start of buf. Returns - 0 if bitPos is greater than or equal to numBits. -*/ +/* FUNC */ +int getBitInBytes(int bitPos, char *buf, int numBits); +/* DESC +Returns the value of the bit bitPos bits from the start of buf. Returns +0 if bitPos is greater than or equal to numBits. +DESC */ -/* ----------------------------------------------------------------------- */ -void putBitInBytes(int bitPos, uint8_t *buf, int val); -/*-------------------------------------------------------------------------*/ -/* Sets the bit bitPos bits from the start of buf to val. -*/ +/* FUNC */ +void putBitInBytes(int bitPos, char *buf, int bit); +/* DESC +Sets the bit bitPos bits from the start of buf to bit. +DESC */ -/*-------------------------------------------------------------------------*/ +/* FUNC */ double time_time(void); -/*-------------------------------------------------------------------------*/ -/* Return the current time in seconds since the Epoch. -*/ +/* DESC +Return the current time in seconds since the Epoch. +DESC */ -/*-------------------------------------------------------------------------*/ +/* FUNC */ void time_sleep(double seconds); -/*-------------------------------------------------------------------------*/ -/* Delay execution for a given number of seconds -*/ +/* DESC +Delay execution for a given number of seconds +DESC */ -/*-------------------------------------------------------------------------*/ +/* FUNC */ void rawDumpWave(void); -/*-------------------------------------------------------------------------*/ -/* Used to print a readable version of the current waveform to stderr. +/* DESC +Used to print a readable version of the current waveform to stderr. - Not intended for general use. -*/ +Not intended for general use. +DESC */ -/*-------------------------------------------------------------------------*/ -void rawDumpScript(int s); -/*-------------------------------------------------------------------------*/ -/* Used to print a readable version of a script to stderr. +/* FUNC */ +void rawDumpScript(unsigned script_id); +/* DESC +Used to print a readable version of a script to stderr. - Not intended for general use. -*/ +Not intended for general use. +DESC */ #ifdef __cplusplus } #endif -/*-------------------------------------------------------------------------*/ +/* PARAMS + +*arg:: +A pointer to a void object passed to a thread started by gpioStartThread. + +bbBaud::100-250000 +The baud rate used for the transmission and reception of bit banged +serial data. + +... +PI_WAVE_MIN_BAUD 100 +PI_WAVE_MAX_BAUD 250000 +... + +bit::0-1 +A value of 0 or 1. + +bitPos:: +A bit position within a byte or word. The least significant bit is +position 0. + +bits:: +A value used to select gpios. If bit n of bits is set then gpio n is +selected. + +A convenient way to set bit n is to or in (1<= 0. + +updateMask:: +A 64 bit mask indicating which gpios may be written to by the user. + +If gpio#n may be written then bit (1<= 0: - pigpio.notify_begin(h, 1234) - ... - """ - return _u2i(_pigpio_command(_control, _PI_CMD_NO, 0, 0)) - -def notify_begin(handle, bits): - """Start notifications on a previously opened handle. - - Returns 0 if OK, otherwise PI_BAD_HANDLE. - - handle: 0-31 (as returned by notify_open()) - bits: a mask indicating the gpios to be notified. - - The notification sends state changes for each gpio whose - corresponding bit in bits is set. - - Example - ... - h = pigpio.notify_open() - if h >= 0: - pigpio.notify_begin(h, 1234) - ... - - This will start notifications for gpios 1, 4, 6, 7, 10 - (1234 = 0x04D2 = 0b0000010011010010). - - Notes - - Each notification occupies 12 bytes in the fifo as follows: - - H (16 bit) seqno - H (16 bit) flags - I (32 bit) tick - I (32 bit) level - - """ - return _u2i(_pigpio_command(_control, _PI_CMD_NB, handle, bits)) - -def notify_pause(handle): - """Pause notifications on a previously opened handle. - - Returns 0 if OK, otherwise PI_BAD_HANDLE. - - handle: 0-31 (as returned by notify_open()) - - Notifications for the handle are suspended until - notify_begin() is called again. - - Example - ... - h = pigpio.notify_open() - if h >= 0: - pigpio.notify_begin(h, 1234) - ... - pigpio.notify_pause(h) - ... - pigpio.notify_begin(h, 1234) - ... - ... - """ - return _u2i(_pigpio_command(_control, _PI_CMD_NB, handle, 0)) - -def notify_close(handle): - """Stop notifications on a previously opened handle and - release the handle for reuse. - - Returns 0 if OK, otherwise PI_BAD_HANDLE. - - handle: 0-31 (as returned by notify_open()) - - Example - ... - h = pigpio.notify_open() - if h >= 0: - pigpio.notify_begin(h, 1234) - ... - pigpio.notify_close(h) - ... - ... - """ - return _u2i(_pigpio_command(_control, _PI_CMD_NC, handle, 0)) - -def set_watchdog(user_gpio, timeout): - """Sets a watchdog for a gpio. - - Returns 0 if OK, otherwise PI_BAD_USER_GPIO - or PI_BAD_WDOG_TIMEOUT. - - user_gpio: 0-31. - timeout: 0-60000. - - The watchdog is nominally in milliseconds. - - Only one watchdog may be registered per gpio. - - The watchdog may be cancelled by setting timeout to 0. - - If no level change has been detected for the gpio for timeout - milliseconds any notification for the gpio has a report written - to the fifo with the flags set to indicate a watchdog timeout. - - The callback() class interprets the flags and will - call registered callbacks for the gpio with level TIMEOUT. - - Example - - #!/usr/bin/env python - - import pigpio - import time - - def cbf(g, L, t): - s = "gpio=" + str(g) + " level=" + str(L) + " at " + str(t) - print(s) - - pigpio.start() - - cb = pigpio.callback(22, pigpio.EITHER_EDGE, cbf) - - print("callback started, 5 second delay") - - time.sleep(5) - - pigpio.set_watchdog(22, 1000) # 1000ms watchdog - - print("watchdog started, 5 second delay") - - time.sleep(5) - - pigpio.set_watchdog(22, 0) # cancel watchdog - - print("watchdog cancelled, 5 second delay") - - time.sleep(5) - - cb.cancel() - - pigpio.stop() - - will print lines such as - - callback started, 5 second delay - watchdog started, 5 second delay - gpio=22 level=2 at 3547411617 - gpio=22 level=2 at 3548411254 - gpio=22 level=2 at 3549411927 - gpio=22 level=2 at 3550412060 - gpio=22 level=2 at 3551411622 - watchdog cancelled, 5 second delay - """ - return _u2i(_pigpio_command(_control, _PI_CMD_WDOG, user_gpio, timeout)) - -def read_bank_1(): - """Read the levels of the bank 1 gpios (gpios 0-31). - - The returned 32 bit integer has a bit set if the corresponding - gpio is logic 1. Gpio n has bit value (1<= 0: - param = struct.unpack('IIIIIIIIII', _control.recv(40)) - return status, param - return status, () - -def stop_script(script_id): - """ - Stops a running script. - - Returns 0 if OK, otherwise PI_BAD_SCRIPT_ID. - - script_id: script_id of stored script. - """ - return _u2i(_pigpio_command(_control, _PI_CMD_PROCS, script_id, 0)) - -def delete_script(script_id): - """ - Deletes a stored script. - - Returns 0 if OK, otherwise PI_BAD_SCRIPT_ID. - - script_id: script_id of stored script. - """ - return _u2i(_pigpio_command(_control, _PI_CMD_PROCD, script_id, 0)) - -def serial_read_open(user_gpio, baud): - """ - This function opens a gpio for reading serial data. - - Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_WAVE_BAUD, - or PI_GPIO_IN_USE. - - The serial data is held in a cyclic buffer and is read using - gpioSerialRead(). - - It is the caller's responsibility to read data from the cyclic buffer - in a timely fashion. - """ - return _u2i(_pigpio_command(_control, _PI_CMD_SLRO, user_gpio, baud)) - -def serial_read(user_gpio): - """ - This function returns data from the serial cyclic buffer. - - It returns a tuple of status and string. The status will be the - length, possibly 0, of the returned string if OK. Otherwise a - negative error code will be returned in which case the string - will be null. - """ - bytes = _u2i(_pigpio_command(_control, _PI_CMD_SLR, user_gpio, 10000)) - if bytes > 0: - buf = "" - while len(buf) < bytes: buf += _control.recv(bytes-len(buf)) - return bytes, buf - return bytes, "" - - -def serial_read_close(user_gpio): - """ - This function closes a gpio for reading serial data. - - Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_NOT_SERIAL_GPIO. - """ - return _u2i(_pigpio_command(_control, _PI_CMD_SLRC, user_gpio, 0)) - - -class callback: +class _callback: """A class to provide gpio level change callbacks.""" - def __init__(self, user_gpio, edge=RISING_EDGE, func=None): - """Initialise a callback and adds it to the notification thread. - - user_gpio: 0-31. - edge: EITHER_EDGE, RISING_EDGE (default), or FALLING_EDGE. - func: user supplied callback function. - - If a user callback is not specified a default tally callback is - provided which simply counts edges. - - The user supplied callback receives three parameters, the gpio, - the level, and the tick. - - Example 1: user supplied edge and callback - - #!/usr/bin/env python - - import pigpio - import time - - def cbf(g, L, t): - s = "gpio=" + str(g) + " level=" + str(L) + " at " + str(t) - print(s) - - pigpio.start() - - cb = pigpio.callback(22, pigpio.EITHER_EDGE, cbf) - - time.sleep(30) - - cb.cancel() - - pigpio.stop() - - will print lines such as - - gpio=22 level=1 at 548556842 - gpio=22 level=0 at 551316679 - gpio=22 level=1 at 553411795 - gpio=22 level=0 at 555269219 - gpio=22 level=1 at 557689701 - - Example 2: user supplied edge, default (tally) callback - - #!/usr/bin/env python - - import pigpio - import time - - pigpio.start() - - pigpio.set_PWM_dutycycle(4, 0) - - pigpio.set_PWM_frequency(4, 2000) - - cb = pigpio.callback(4, pigpio.EITHER_EDGE) - - pigpio.set_PWM_dutycycle(4, 128) # half power - - tally_1 = cb.tally() - - time.sleep(50) - - tally_2 = cb.tally() - - s = "counted " + str(tally_2 - tally_1) + " edges" - - print(s) - - cb.cancel() - - pigpio.stop() - - will print a line such as - - counted 200200 edges - - Example 3: default edge and (tally) callback - - #!/usr/bin/env python - - import pigpio - import time - - pigpio.start() - - pigpio.set_PWM_dutycycle(17, 0) - - pigpio.set_PWM_frequency(17, 2000) - - cb = pigpio.callback(17) - - pigpio.set_PWM_dutycycle(17, 64) # quarter power - - tally_1 = cb.tally() - - time.sleep(50) - - tally_2 = cb.tally() - - s = "counted " + str(tally_2 - tally_1) + " rising edges" - - print(s) - - cb.cancel() - - pigpio.stop() - - will print a line such as - - counted 100101 rising edges - + def __init__(self, notify, user_gpio, edge=RISING_EDGE, func=None): """ + Initialise a callback and adds it to the notification thread. + """ + self._notify = notify self.count=0 if func is None: func=self._tally - self.callb = _callback(user_gpio, edge, func) - _notify.append(self.callb) + self.callb = _callback_ADT(user_gpio, edge, func) + self._notify.append(self.callb) def cancel(self): """Cancels a callback by removing it from the notification thread.""" - _notify.remove(self.callb) + self._notify.remove(self.callb) def _tally(self, user_gpio, level, tick): - """Increment the callback called count. - - user_gpio: - level: - tick: - """ + """Increment the callback called count.""" self.count += 1 def tally(self): - """Provides a count of how many times the default tally + """ + Provides a count of how many times the default tally callback has triggered. The count will be zero if the user has supplied their own @@ -2052,150 +802,2137 @@ class callback: """ return self.count +class _wait_for_edge: + """Encapsulates waiting for gpio edges.""" -def wait_for_edge(user_gpio, edge=RISING_EDGE, timeout=60.0): - """Wait for an edge event on a gpio. + def __init__(self, notify, gpio, edge, timeout): + """Initialises a wait_for_edge.""" + self._notify = notify + self.callb = _callback_ADT(gpio, edge, self.func) + self.trigger = False + self._notify.append(self.callb) + self.start = time.time() + while (self.trigger == False) and ((time.time()-self.start) < timeout): + time.sleep(0.05) + self._notify.remove(self.callb) - The function returns as soon as the edge is detected - or after the number of seconds specified by timeout has - expired. + def func(self, gpio, level, tick): + """Sets wait_for_edge triggered.""" + self.trigger = True - user_gpio: 0-31. - edge: EITHER_EDGE, RISING_EDGE (default), or FALLING_EDGE. - timeout: 0.0- (default 60.0). +class pi(): - The function returns True if the edge is detected, - otherwise False. + def _rxbuf(self, count): + """Returns count bytes from the command socket.""" + ext = bytearray(self._control.recv(count)) + while len(ext) < count: + ext.extend(self._control.recv(count - len(ext))) + return ext - Example 1: default edge and timeout + def set_mode(self, gpio, mode): + """ + Sets the gpio mode. - #!/usr/bin/env python + gpio:= 0-53. + mode:= INPUT, OUTPUT, ALT0, ALT1, ALT2, ALT3, ALT4, ALT5. - import pigpio - import time + ... + pi.set_mode( 4, pigpio.INPUT) # gpio 4 as input + pi.set_mode(17, pigpio.OUTPUT) # gpio 17 as output + pi.set_mode(24, pigpio.ALT2) # gpio 24 as ALT2 + ... + """ + return _u2i(_pigpio_command(self._control, _PI_CMD_MODES, gpio, mode)) - pigpio.start() + def get_mode(self, gpio): + """ + Returns the gpio mode. - if pigpio.wait_for_edge(23): - print("Rising edge detected") - else: - print("wait for edge timed out") + gpio:= 0-53. - pigpio.stop() + Returns a value as follows - will print + . . + 0 = INPUT + 1 = OUTPUT + 2 = ALT5 + 3 = ALT4 + 4 = ALT0 + 5 = ALT1 + 6 = ALT2 + 7 = ALT3 + . . - Rising edge detected + ... + print(pi.get_mode(0)) + 4 + ... + """ + return _u2i(_pigpio_command(self._control, _PI_CMD_MODEG, gpio, 0)) - or + def set_pull_up_down(self, gpio, pud): + """ + Sets or clears the internal gpio pull-up/down resistor. - wait for edge timed out + gpio:= 0-53. + pud:= PUD_UP, PUD_DOWN, PUD_OFF. - Example 2: user supplied edge and timeout + ... + pi.set_pull_up_down(17, pigpio.PUD_OFF) + pi.set_pull_up_down(23, pigpio.PUD_UP) + pi.set_pull_up_down(24, pigpio.PUD_DOWN) + ... + """ + return _u2i(_pigpio_command(self._control, _PI_CMD_PUD, gpio, pud)) - #!/usr/bin/env python + def read(self, gpio): + """ + Returns the gpio level. - import pigpio - import time + gpio:= 0-53. - pigpio.start() + ... + pi.set_mode(23, pigpio.INPUT) - if pigpio.wait_for_edge(23, pigpio.FALLING_EDGE, 5.0): - print("Falling edge detected") - else: - print("wait for falling edge timed out") + pi.set_pull_up_down(23, pigpio.PUD_DOWN) + print(pi.read(23)) + 0 - pigpio.stop() + pi.set_pull_up_down(23, pigpio.PUD_UP) + print(pi.read(23)) + 1 + ... + """ + return _u2i(_pigpio_command(self._control, _PI_CMD_READ, gpio, 0)) + def write(self, gpio, level): + """ + Sets the gpio level. - will print + gpio:= 0-53. + level:= 0, 1. - Falling edge detected + If PWM or servo pulses are active on the gpio they are + switched off. - or + ... + pi.set_mode(17, pigpio.OUTPUT) - wait for falling edge timed out + pi.write(17,0) + print(pi.read(17)) + 0 + pi.write(17,1) + print(pi.read(17)) + 1 + ... + """ + return _u2i(_pigpio_command(self._control, _PI_CMD_WRITE, gpio, level)) + + def set_PWM_dutycycle(self, user_gpio, dutycycle): + """ + Starts (non-zero dutycycle) or stops (0) PWM pulses on the gpio. + + user_gpio:= 0-31. + dutycycle:= 0-range (range defaults to 255). + + The set_PWM_range function can change the default range of 255. + + ... + pi.set_PWM_dutycycle(4, 0) # PWM off + pi.set_PWM_dutycycle(4, 64) # PWM 1/4 on + pi.set_PWM_dutycycle(4, 128) # PWM 1/2 on + pi.set_PWM_dutycycle(4, 192) # PWM 3/4 on + pi.set_PWM_dutycycle(4, 255) # PWM full on + ... + """ + return _u2i(_pigpio_command( + self._control, _PI_CMD_PWM, user_gpio, int(dutycycle))) + + def set_PWM_range(self, user_gpio, range_): + """ + Sets the range of PWM values to be used on the gpio. + + user_gpio:= 0-31. + range_:= 25-40000. + + ... + pi.set_PWM_range(9, 100) # now 25 1/4, 50 1/2, 75 3/4 on + pi.set_PWM_range(9, 500) # now 125 1/4, 250 1/2, 375 3/4 on + pi.set_PWM_range(9, 3000) # now 750 1/4, 1500 1/2, 2250 3/4 on + ... + """ + return _u2i(_pigpio_command(self._control, _PI_CMD_PRS, user_gpio, range_)) + + def get_PWM_range(self, user_gpio): + """ + Returns the range of PWM values being used on the gpio. + + user_gpio:= 0-31. + + ... + pi.set_PWM_range(9, 500) + print(pi.get_PWM_range(9)) + 500 + ... + """ + return _u2i(_pigpio_command(self._control, _PI_CMD_PRG, user_gpio, 0)) + + def get_PWM_real_range(self, user_gpio): + """ + Returns the real (underlying) range of PWM values being + used on the gpio. + + user_gpio:= 0-31. + + ... + pi.set_PWM_frequency(4, 800) + print(pi.get_PWM_real_range(4)) + 250 + ... + """ + return _u2i(_pigpio_command(self._control, _PI_CMD_PRRG, user_gpio, 0)) + + def set_PWM_frequency(self, user_gpio, frequency): + """ + Sets the frequency (in Hz) of the PWM to be used on the gpio. + + user_gpio:= 0-31. + frequency:= >=0 Hz + + Returns the frequency actually set. + + ... + pi.set_PWM_frequency(4,0) + print(pi.get_PWM_frequency(4)) + 10 + + pi.set_PWM_frequency(4,100000) + print(pi.get_PWM_frequency(4)) + 8000 + ... + """ + return _u2i(_pigpio_command(self._control, _PI_CMD_PFS, user_gpio, frequency)) + + def get_PWM_frequency(self, user_gpio): + """ + Returns the frequency of PWM being used on the gpio. + + user_gpio:= 0-31. + + Returns the frequency (in Hz) used for the gpio. + + ... + pi.set_PWM_frequency(4,0) + print(pi.get_PWM_frequency(4)) + 10 + + pi.set_PWM_frequency(4, 800) + print(pi.get_PWM_frequency(4)) + 800 + ... + """ + return _u2i(_pigpio_command(self._control, _PI_CMD_PFG, user_gpio, 0)) + + def set_servo_pulsewidth(self, user_gpio, pulsewidth): + """ + Starts (500-2500) or stops (0) servo pulses on the gpio. + + user_gpio:= 0-31. + pulsewidth:= 0 (off), + 500 (most anti-clockwise) - 2500 (most clockwise). + + The selected pulsewidth will continue to be transmitted until + changed by a subsequent call to set_servo_pulsewidth. + + The pulsewidths supported by servos varies and should probably + be determined by experiment. A value of 1500 should always be + safe and represents the mid-point of rotation. + + You can DAMAGE a servo if you command it to move beyond its + limits. + + ... + pi.set_servo_pulsewidth(17, 0) # off + pi.set_servo_pulsewidth(17, 1000) # safe anti-clockwise + pi.set_servo_pulsewidth(17, 1500) # centre + pi.set_servo_pulsewidth(17, 2000) # safe clockwise + ... """ - a = _wait_for_edge(user_gpio, edge, timeout) - return a.trigger + return _u2i(_pigpio_command( + self._control, _PI_CMD_SERVO, user_gpio, int(pulsewidth))) -def start(host = os.getenv("PIGPIO_ADDR", ''), - port = os.getenv("PIGPIO_PORT", 8888)): - """Start the pigpio module. + def notify_open(self): + """ + Returns a notification handle (>=0). - host: the host name of the Pi on which the pigpio daemon is running. - The default is localhost unless overwritten by the PIGPIO_ADDR - environment variable. - port: the port number on which the pigpio daemon is listening. - The default is 8888 unless overwritten by the PIGPIO_PORT - environment variable. The pigpiod must have been started - with the same port number. + A notification is a method for being notified of gpio state + changes via a pipe. - The function connects to the pigpio daemon and reserves resources - to be used for sending commands and receiving notifications. + Pipes are only accessible from the local machine so this + function serves no purpose if you are using Python from a + remote machine. The in-built (socket) notifications + provided by callback should be used instead. - EXAMPLES: - ... - pigpio.start() # use defaults + Notifications for handle x will be available at the pipe + named /dev/pigpiox (where x is the handle number). + E.g. if the function returns 15 then the notifications must be + read from /dev/pigpio15. - pigpio.start('mypi') # specify host, default port + Notifications have the following structure. - pigpio.start('mypi', 7777) # specify host and port - ... - """ + . . + I seqno - increments for each report + I flags - flags, if bit 5 is set then bits 0-4 of the flags + indicate a gpio which has had a watchdog timeout. + I tick - time of sample. + I level - 32 bits of levels for gpios 0-31. + . . - global _control, _notify - global _host, _port + ... + h = pi.notify_open() + if h >= 0: + pi.notify_begin(h, 1234) + ... + """ + return _u2i(_pigpio_command(self._control, _PI_CMD_NO, 0, 0)) - _host = host - _port = int(port) + def notify_begin(self, handle, bits): + """ + Starts notifications on a handle. - _control = socket.socket(socket.AF_INET, socket.SOCK_STREAM) + handle:= >=0 (as returned by a prior call to notify_open) + bits:= a 32 bit mask indicating the gpios to be notified. - try: - _control.connect((_host, _port)) - _notify = _callback_thread() - except socket.error: - if _control is not None: - _control = None - if _host == '': - h = "localhost" + The notification sends state changes for each gpio whose + corresponding bit in bits is set. + + The following code starts notifications for gpios 1, 4, + 6, 7, and 10 (1234 = 0x04D2 = 0b0000010011010010). + + ... + h = pi.notify_open() + if h >= 0: + pi.notify_begin(h, 1234) + ... + """ + return _u2i(_pigpio_command(self._control, _PI_CMD_NB, handle, bits)) + + def notify_pause(self, handle): + """ + Pauses notifications on a handle. + + handle:= >=0 (as returned by a prior call to notify_open) + + Notifications for the handle are suspended until + notify_begin is called again. + + ... + h = pi.notify_open() + if h >= 0: + pi.notify_begin(h, 1234) + ... + pi.notify_pause(h) + ... + pi.notify_begin(h, 1234) + ... + ... + """ + return _u2i(_pigpio_command(self._control, _PI_CMD_NB, handle, 0)) + + def notify_close(self, handle): + """ + Stops notifications on a handle and releases the handle for reuse. + + handle:= >=0 (as returned by a prior call to notify_open) + + ... + h = pi.notify_open() + if h >= 0: + pi.notify_begin(h, 1234) + ... + pi.notify_close(h) + ... + ... + """ + return _u2i(_pigpio_command(self._control, _PI_CMD_NC, handle, 0)) + + def set_watchdog(self, user_gpio, wdog_timeout): + """ + Sets a watchdog timeout for a gpio. + + user_gpio:= 0-31. + wdog_timeout:= 0-60000. + + The watchdog is nominally in milliseconds. + + Only one watchdog may be registered per gpio. + + The watchdog may be cancelled by setting timeout to 0. + + If no level change has been detected for the gpio for timeout + milliseconds any notification for the gpio has a report written + to the fifo with the flags set to indicate a watchdog timeout. + + The callback class interprets the flags and will + call registered callbacks for the gpio with level TIMEOUT. + + ... + pi.set_watchdog(23, 1000) # 1000 ms watchdog on gpio 23 + pi.set_watchdog(23, 0) # cancel watchdog on gpio 23 + ... + """ + return _u2i(_pigpio_command( + self._control, _PI_CMD_WDOG, user_gpio, int(wdog_timeout))) + + def read_bank_1(self): + """ + Returns the levels of the bank 1 gpios (gpios 0-31). + + The returned 32 bit integer has a bit set if the corresponding + gpio is high. Gpio n has bit value (1<=0) if OK. + + The data provided by the wave_add_* functions is consumed by + this function. + + As many waveforms may be created as there is space available. + The wave id is passed to wave_send_* to specify the waveform + to transmit. + + Normal usage would be + + Step 1. wave_clear to clear all waveforms and added data. + + Step 2. wave_add_* calls to supply the waveform data. + + Step 3. wave_create to create the waveform and get a unique id + + Repeat steps 2 and 3 as needed. + + Step 4. wave_send_* with the id of the waveform to transmit. + + A waveform comprises one or more pulses. + + A pulse specifies + + 1) the gpios to be switched on at the start of the pulse. + 2) the gpios to be switched off at the start of the pulse. + 3) the delay in microseconds before the next pulse. + + Any or all the fields can be zero. It doesn't make any sense + to set all the fields to zero (the pulse will be ignored). + + When a waveform is started each pulse is executed in order with + the specified delay between the pulse and the next. + + ... + wid = pi.wave_create() + ... + """ + return _u2i(_pigpio_command(self._control, _PI_CMD_WVCRE, 0, 0)) + + def wave_delete(self, wave_id): + """ + Deletes all created waveforms with ids greater than or equal + to wave_id. + + wave_id:= >=0 (as returned by a prior call to wave_create). + + Wave ids are allocated in order, 0, 1, 2, etc. + + ... + pi.wave_delete(6) # delete all waves with id 6 or greater + + pi.wave_delete(0) # delete all waves + ... + """ + return _u2i(_pigpio_command(self._control, _PI_CMD_WVDEL, wave_id, 0)) + + def wave_tx_start(self): # DEPRECATED + """ + This function is deprecated and will be removed. + + Use wave_create/wave_send_* instead. + """ + return _u2i(_pigpio_command(self._control, _PI_CMD_WVGO, 0, 0)) + + def wave_tx_repeat(self): # DEPRECATED + """ + This function is deprecated and will be removed. + + Use wave_create/wave_send_* instead. + """ + return _u2i(_pigpio_command(self._control, _PI_CMD_WVGOR, 0, 0)) + + def wave_send_once(self, wave_id): + """ + Transmits the waveform with id wave_id. The waveform is sent + once. + + wave_id:= >=0 (as returned by a prior call to wave_create). + + Returns the number of DMA control blocks used in the waveform. + + ... + cbs = pi.wave_send_once(wid) + ... + """ + return _u2i(_pigpio_command(self._control, _PI_CMD_WVTX, wave_id, 0)) + + def wave_send_repeat(self, wave_id): + """ + Transmits the waveform with id wave_id. The waveform repeats + until wave_tx_stop is called or another call to wave_send_* + is made. + + wave_id:= >=0 (as returned by a prior call to wave_create). + + Returns the number of DMA control blocks used in the waveform. + + ... + cbs = pi.wave_send_repeat(wid) + ... + """ + return _u2i(_pigpio_command(self._control, _PI_CMD_WVTXR, wave_id, 0)) + + def wave_tx_busy(self): + """ + Returns 1 if a waveform is currently being transmitted, + otherwise 0. + + ... + pi.wave_send_once(0) # send first waveform + + while pi.wave_tx_busy(): # wait for waveform to be sent + time.sleep(0.1) + + pi.wave_send_once(1) # send next waveform + ... + """ + return _u2i(_pigpio_command(self._control, _PI_CMD_WVBSY, 0, 0)) + + def wave_tx_stop(self): + """ + Stops the transmission of the current waveform. + + This function is intended to stop a waveform started with + wave_send_repeat. + + ... + pi.wave_send_repeat(3) + + time.sleep(5) + + pi.wave_tx_stop() + ... + """ + return _u2i(_pigpio_command(self._control, _PI_CMD_WVHLT, 0, 0)) + + def wave_get_micros(self): + """ + Returns the length in microseconds of the current waveform. + + ... + micros = pi.wave_get_micros() + ... + """ + return _u2i(_pigpio_command(self._control, _PI_CMD_WVSM, 0, 0)) + + def wave_get_max_micros(self): + """ + Returns the maximum possible size of a waveform in microseconds. + + ... + micros = pi.wave_get_max_micros() + ... + """ + return _u2i(_pigpio_command(self._control, _PI_CMD_WVSM, 2, 0)) + + def wave_get_pulses(self): + """ + Returns the length in pulses of the current waveform. + + ... + pulses = pi.wave_get_pulses() + ... + """ + return _u2i(_pigpio_command(self._control, _PI_CMD_WVSP, 0, 0)) + + def wave_get_max_pulses(self): + """ + Returns the maximum possible size of a waveform in pulses. + + ... + pulses = pi.wave_get_max_pulses() + ... + """ + return _u2i(_pigpio_command(self._control, _PI_CMD_WVSP, 2, 0)) + + def wave_get_cbs(self): + """ + Returns the length in DMA control blocks of the current + waveform. + + ... + cbs = pi.wave_get_cbs() + ... + """ + return _u2i(_pigpio_command(self._control, _PI_CMD_WVSC, 0, 0)) + + def wave_get_max_cbs(self): + """ + Returns the maximum possible size of a waveform in DMA + control blocks. + + ... + cbs = pi.wave_get_max_cbs() + ... + """ + return _u2i(_pigpio_command(self._control, _PI_CMD_WVSC, 2, 0)) + + def i2c_open(self, i2c_bus, i2c_address, i2c_flags=0): + """ + Returns a handle (>=0) for the device at the I2C bus address. + + i2c_bus:= 0-1. + i2c_address:= 0x08-0x77. + i2c_flags:= 0, no flags are currently defined. + + ... + h = pi.i2c_open(1, 0x53) # open device at address 0x53 on bus 1 + ... + """ + # I p1 i2c_bus + # I p2 i2c_addr + # I p3 4 + ## extension ## + # I i2c_flags + extents = [struct.pack("I", i2c_flags)] + return _u2i(_pigpio_command_ext( + self._control, _PI_CMD_I2CO, i2c_bus, i2c_address, 4, extents)) + + def i2c_close(self, handle): + """ + Closes the I2C device associated with handle. + + handle:= >=0 (as returned by a prior call to i2c_open). + + ... + pi.i2c_close(h) + ... + """ + return _u2i(_pigpio_command(self._control, _PI_CMD_I2CC, handle, 0)) + + def i2c_read_device(self, handle, count): + """ + Returns count bytes read from the raw device associated + with handle. + + handle:= >=0 (as returned by a prior call to i2c_open). + count:= >0, the number of bytes to read. + + The returned value is a tuple of the number of bytes read and a + bytearray containing the bytes. If there was an error the + number of bytes read will be less than zero (and will contain + the error code). + + ... + (count, data) = pi.i2c_read_device(h, 12) + ... + """ + bytes = _u2i(_pigpio_command(self._control, _PI_CMD_I2CRD, handle, count)) + if bytes > 0: + return bytes, self._rxbuf(bytes) + return bytes, "" + + def i2c_write_device(self, handle, data): + """ + Writes the data bytes to the raw device associated with handle. + + handle:= >=0 (as returned by a prior call to i2c_open). + data:= the bytes to write. + + ... + pi.i2c_write_device(h, b"\\x12\\x34\\xA8") + + pi.i2c_write_device(h, b"help") + + pi.i2c_write_device(h, 'help') + + pi.i2c_write_device(h, [23, 56, 231]) + ... + """ + # I p1 handle + # I p2 0 + # I p3 len + ## extension ## + # s len data bytes + if len(data): + return _u2i(_pigpio_command_ext( + self._control, _PI_CMD_I2CWD, handle, 0, len(data), [data])) + else: + return 0 + + def i2c_write_quick(self, handle, bit): + """ + Sends a single bit to the device associated with handle + (smbus 2.0 5.5.1 - Quick command). + + handle:= >=0 (as returned by a prior call to i2c_open). + bit:= 0 or 1, the value to write. + + ... + pi.i2c_write_quick(0, 1) # send 1 to device 0 + pi.i2c_write_quick(3, 0) # send 0 to device 3 + ... + """ + return _u2i(_pigpio_command(self._control, _PI_CMD_I2CWQ, handle, bit)) + + def i2c_write_byte(self, handle, byte_val): + """ + Sends a single byte to the device associated with handle + (smbus 2.0 5.5.2 - Send byte). + + handle:= >=0 (as returned by a prior call to i2c_open). + byte_val:= 0-255, the value to write. + + ... + pi.i2c_write_byte(1, 17) # send byte 17 to device 1 + pi.i2c_write_byte(2, 0x23) # send byte 0x23 to device 2 + ... + """ + return _u2i( + _pigpio_command(self._control, _PI_CMD_I2CWS, handle, byte_val)) + + def i2c_read_byte(self, handle): + """ + Reads a single byte from the device associated with handle + (smbus 2.0 5.5.3 - Receive byte). + + handle:= >=0 (as returned by a prior call to i2c_open). + + ... + b = pi.i2c_read_byte(2) # read a byte from device 2 + ... + """ + return _u2i(_pigpio_command(self._control, _PI_CMD_I2CRS, handle, 0)) + + def i2c_write_byte_data(self, handle, reg, byte_val): + """ + Writes a single byte to the specified register of the device + associated with handle (smbus 2.0 5.5.4 - Write byte). + + handle:= >=0 (as returned by a prior call to i2c_open). + reg:= >=0, the device register. + byte_val:= 0-255, the value to write. + + ... + # send byte 0xC5 to reg 2 of device 1 + pi.i2c_write_byte_data(1, 2, 0xC5) + + # send byte 9 to reg 4 of device 2 + pi.i2c_write_byte_data(2, 4, 9) + ... + """ + # I p1 handle + # I p2 reg + # I p3 4 + ## extension ## + # I byte_val + extents = [struct.pack("I", byte_val)] + return _u2i(_pigpio_command_ext( + self._control, _PI_CMD_I2CWB, handle, reg, 4, extents)) + + def i2c_write_word_data(self, handle, reg, word_val): + """ + Writes a single 16 bit word to the specified register of the + device associated with handle (smbus 2.0 5.5.4 - Write word). + + handle:= >=0 (as returned by a prior call to i2c_open). + reg:= >=0, the device register. + word_val:= 0-65535, the value to write. + + ... + # send word 0xA0C5 to reg 5 of device 4 + pi.i2c_write_word_data(4, 5, 0xA0C5) + + # send word 2 to reg 2 of device 5 + pi.i2c_write_word_data(5, 2, 23) + ... + """ + # I p1 handle + # I p2 reg + # I p3 4 + ## extension ## + # I word_val + extents = [struct.pack("I", word_val)] + return _u2i(_pigpio_command_ext( + self._control, _PI_CMD_I2CWW, handle, reg, 4, extents)) + + def i2c_read_byte_data(self, handle, reg): + """ + Reads a single byte from the specified register of the device + associated with handle (smbus 2.0 5.5.5 - Read byte). + + handle:= >=0 (as returned by a prior call to i2c_open). + reg:= >=0, the device register. + + ... + # read byte from reg 17 of device 2 + b = pi.i2c_read_byte_data(2, 17) + + # read byte from reg 1 of device 0 + b = pi.i2c_read_byte_data(0, 1) + ... + """ + return _u2i(_pigpio_command(self._control, _PI_CMD_I2CRB, handle, reg)) + + def i2c_read_word_data(self, handle, reg): + """ + Reads a single 16 bit word from the specified register of the + device associated with handle (smbus 2.0 5.5.5 - Read word). + + handle:= >=0 (as returned by a prior call to i2c_open). + reg:= >=0, the device register. + + ... + # read word from reg 2 of device 3 + w = pi.i2c_read_word_data(3, 2) + + # read word from reg 7 of device 2 + w = pi.i2c_read_word_data(2, 7) + ... + """ + return _u2i(_pigpio_command(self._control, _PI_CMD_I2CRW, handle, reg)) + + def i2c_process_call(self, handle, reg, word_val): + """ + Writes 16 bits of data to the specified register of the device + associated with handle and reads 16 bits of data in return + (smbus 2.0 5.5.6 - Process call). + + handle:= >=0 (as returned by a prior call to i2c_open). + reg:= >=0, the device register. + word_val:= 0-65535, the value to write. + + ... + r = pi.i2c_process_call(h, 4, 0x1231) + r = pi.i2c_process_call(h, 6, 0) + ... + """ + # I p1 handle + # I p2 reg + # I p3 4 + ## extension ## + # I word_val + extents = [struct.pack("I", word_val)] + return _u2i(_pigpio_command_ext( + self._control, _PI_CMD_I2CPC, handle, reg, 4, extents)) + + def i2c_write_block_data(self, handle, reg, data): + """ + Writes up to 32 bytes to the specified register of the device + associated with handle (smbus 2.0 5.5.7 - Block write). + + handle:= >=0 (as returned by a prior call to i2c_open). + reg:= >=0, the device register. + data:= the bytes to write. + + ... + pi.i2c_write_block_data(4, 5, b'hello') + + pi.i2c_write_block_data(4, 5, "data bytes") + + pi.i2c_write_block_data(5, 0, b'\\x00\\x01\\x22') + + pi.i2c_write_block_data(6, 2, [0, 1, 0x22]) + ... + """ + # I p1 handle + # I p2 reg + # I p3 len + ## extension ## + # s len data bytes + if len(data): + return _u2i(_pigpio_command_ext( + self._control, _PI_CMD_I2CWK, handle, reg, len(data), [data])) + else: + return 0 + + def i2c_read_block_data(self, handle, reg): + """ + Reads a block of up to 32 bytes from the specified register of + the device associated with handle (smbus 2.0 5.5.7 - Block read). + + handle:= >=0 (as returned by a prior call to i2c_open). + reg:= >=0, the device register. + + The amount of returned data is set by the device. + + The returned value is a tuple of the number of bytes read and a + bytearray containing the bytes. If there was an error the + number of bytes read will be less than zero (and will contain + the error code). + + ... + (b, d) = pi.i2c_read_block_data(h, 10) + if b >= 0: + # process data + else: + # process read failure + ... + """ + bytes = _u2i(_pigpio_command(self._control, _PI_CMD_I2CRK, handle, reg)) + if bytes > 0: + return bytes, self._rxbuf(bytes) + return bytes, "" + + def i2c_block_process_call(self, handle, reg, data): + """ + Writes data bytes to the specified register of the device + associated with handle and reads a device specified number + of bytes of data in return (smbus 2.0 5.5.8 - + Block write-block read). + + handle:= >=0 (as returned by a prior call to i2c_open). + reg:= >=0, the device register. + data:= the bytes to write. + + The smbus 2.0 documentation states that a minimum of 1 byte may + be sent and a minimum of 1 byte may be received. The total + number of bytes sent/received must be 32 or less. + + The returned value is a tuple of the number of bytes read and a + bytearray containing the bytes. If there was an error the + number of bytes read will be less than zero (and will contain + the error code). + + ... + (b, d) = pi.i2c_block_process_call(h, 10, b'\\x02\\x05\\x00') + + (b, d) = pi.i2c_block_process_call(h, 10, b'abcdr') + + (b, d) = pi.i2c_block_process_call(h, 10, "abracad") + + (b, d) = pi.i2c_block_process_call(h, 10, [2, 5, 16]) + ... + """ + # I p1 handle + # I p2 reg + # I p3 len + ## extension ## + # s len data bytes + bytes = _u2i(_pigpio_command_ext( + self._control, _PI_CMD_I2CPK, handle, reg, len(data), [data])) + if bytes > 0: + return bytes, self._rxbuf(bytes) + return bytes, "" + + def i2c_write_i2c_block_data(self, handle, reg, data): + """ + Writes data bytes to the specified register of the device + associated with handle . 1-32 bytes may be written. + + handle:= >=0 (as returned by a prior call to i2c_open). + reg:= >=0, the device register. + data:= the bytes to write. + + ... + pi.i2c_write_i2c_block_data(4, 5, 'hello') + + pi.i2c_write_i2c_block_data(4, 5, b'hello') + + pi.i2c_write_i2c_block_data(5, 0, b'\\x00\\x01\\x22') + + pi.i2c_write_i2c_block_data(6, 2, [0, 1, 0x22]) + ... + """ + # I p1 handle + # I p2 reg + # I p3 len + ## extension ## + # s len data bytes + if len(data): + return _u2i(_pigpio_command_ext( + self._control, _PI_CMD_I2CWI, handle, reg, len(data), [data])) + else: + return 0 + + def i2c_read_i2c_block_data(self, handle, reg, count): + """ + Reads count bytes from the specified register of the device + associated with handle . The count may be 1-32. + + handle:= >=0 (as returned by a prior call to i2c_open). + reg:= >=0, the device register. + count:= >0, the number of bytes to read. + + The returned value is a tuple of the number of bytes read and a + bytearray containing the bytes. If there was an error the + number of bytes read will be less than zero (and will contain + the error code). + + ... + (b, d) = pi.i2c_read_i2c_block_data(h, 4, 32) + if b >= 0: + # process data + else: + # process read failure + ... + """ + # I p1 handle + # I p2 reg + # I p3 4 + ## extension ## + # I count + extents = [struct.pack("I", count)] + bytes = _u2i(_pigpio_command_ext( + self._control, _PI_CMD_I2CRI, handle, reg, 4, extents)) + if bytes > 0: + return bytes, self._rxbuf(bytes) + return bytes, "" + + def spi_open(self, spi_channel, spi_baud, spi_flags=0): + """ + Returns a handle for the SPI device on channel. + + spi_channel:= 0 or 1, the SPI channel. + spi_baud:= >0, the transmission rate in bits per second. + spi_flags:= see below. + + The bottom two bits of spi_flags define the SPI mode as + follows. + + . . + bit bit + 1 0 + POL PHA Mode + 0 0 0 + 0 1 1 + 1 0 2 + 1 1 3 + . . + + The other bits in spi_flags should be set to zero. + + ... + # open SPI device on channel 1 in mode 3 at 20000 bits per second + + h = pi.spi_open(1, 20000, 3) + ... + """ + # I p1 spi_channel + # I p2 spi_baud + # I p3 4 + ## extension ## + # I spi_flags + extents = [struct.pack("I", spi_flags)] + return _u2i(_pigpio_command_ext( + self._control, _PI_CMD_SPIO, spi_channel, spi_baud, 4, extents)) + + def spi_close(self, handle): + """ + Closes the SPI device associated with handle. + + handle:= >=0 (as returned by a prior call to spi_open). + + ... + pi.spi_close(h) + ... + """ + return _u2i(_pigpio_command(self._control, _PI_CMD_SPIC, handle, 0)) + + def spi_read(self, handle, count): + """ + Reads count bytes from the SPI device associated with handle. + + handle:= >=0 (as returned by a prior call to spi_open). + count:= >0, the number of bytes to read. + + The returned value is a tuple of the number of bytes read and a + bytearray containing the bytes. If there was an error the + number of bytes read will be less than zero (and will contain + the error code). + + ... + (b, d) = pi.spi_read(h, 60) # read 60 bytes from device h + if b == 60: + # process read data + else: + # error path + ... + """ + bytes = _u2i(_pigpio_command( + self._control, _PI_CMD_SPIR, handle, count)) + if bytes > 0: + return bytes, self._rxbuf(bytes) + return bytes, "" + + def spi_write(self, handle, data): + """ + Writes the data bytes to the SPI device associated with handle. + + handle:= >=0 (as returned by a prior call to spi_open). + data:= the bytes to write. + + ... + pi.spi_write(0, b'\\x02\\xc0\\x80') # write 3 bytes to device 0 + + pi.spi_write(0, b'defgh') # write 5 bytes to device 0 + + pi.spi_write(0, "def") # write 3 bytes to device 0 + + pi.spi_write(1, [2, 192, 128]) # write 3 bytes to device 1 + ... + """ + # I p1 handle + # I p2 0 + # I p3 len + ## extension ## + # s len data bytes + return _u2i(_pigpio_command_ext( + self._control, _PI_CMD_SPIW, handle, 0, len(data), [data])) + + def spi_xfer(self, handle, data): + """ + Writes the data bytes to the SPI device associated with handle, + returning the data bytes read from the device. + + handle:= >=0 (as returned by a prior call to spi_open). + data:= the bytes to write. + + The returned value is a tuple of the number of bytes read and a + bytearray containing the bytes. If there was an error the + number of bytes read will be less than zero (and will contain + the error code). + + ... + (count, rx_data) = pi.spi_xfer(h, b'\\x01\\x80\\x00') + + (count, rx_data) = pi.spi_xfer(h, [1, 128, 0]) + + (count, rx_data) = pi.spi_xfer(h, b"hello") + + (count, rx_data) = pi.spi_xfer(h, "hello") + ... + """ + # I p1 handle + # I p2 0 + # I p3 len + ## extension ## + # s len data bytes + bytes = _u2i(_pigpio_command_ext( + self._control, _PI_CMD_SPIX, handle, 0, len(data), [data])) + if bytes > 0: + return bytes, self._rxbuf(bytes) + return bytes, "" + + def serial_open(self, tty, ser_baud, ser_flags=0): + """ + Returns a handle for the serial tty device opened + at ser_baud bits per second. + + tty:= the serial device to open. + ser_baud:= baud rate + ser_flags:= 0, no flags are currently defined. + + ... + h1 = pi.serial_open("/dev/ttyAMA0", 300) + + h2 = pi.serial_open("/dev/ttyUSB1", 19200, 0) + ... + """ + # I p1 ser_baud + # I p2 ser_flags + # I p3 len + ## extension ## + # s len data bytes + return _u2i(_pigpio_command_ext( + self._control, _PI_CMD_SERO, ser_baud, ser_flags, len(tty), [tty])) + + def serial_close(self, handle): + """ + Closes the serial device associated with handle. + + handle:= >=0 (as returned by a prior call to serial_open). + + ... + pi.serial_close(h1) + ... + """ + return _u2i(_pigpio_command(self._control, _PI_CMD_SERC, handle, 0)) + + def serial_read_byte(self, handle): + """ + Returns a single byte from the device associated with handle. + + handle:= >=0 (as returned by a prior call to serial_open). + + ... + b = pi.serial_read_byte(h1) + ... + """ + return _u2i(_pigpio_command(self._control, _PI_CMD_SERRB, handle, 0)) + + def serial_write_byte(self, handle, byte_val): + """ + Writes a single byte to the device associated with handle. + + handle:= >=0 (as returned by a prior call to serial_open). + byte_val:= 0-255, the value to write. + + ... + pi.serial_write_byte(h1, 23) + + pi.serial_write_byte(h1, ord('Z')) + ... + """ + return _u2i( + _pigpio_command(self._control, _PI_CMD_SERWB, handle, byte_val)) + + def serial_read(self, handle, count): + """ + Reads up to count bytes from the device associated with handle. + + handle:= >=0 (as returned by a prior call to serial_open). + count:= >0, the number of bytes to read. + + The returned value is a tuple of the number of bytes read and a + bytearray containing the bytes. If there was an error the + number of bytes read will be less than zero (and will contain + the error code). + + ... + (b, d) = pi.serial_read(h2, 100) + if b > 0: + # process read data + ... + """ + bytes = _u2i(_pigpio_command(self._control, _PI_CMD_SERR, handle, count)) + + if bytes > 0: + return bytes, self._rxbuf(bytes) + return bytes, "" + + def serial_write(self, handle, data): + """ + Writes the data bytes to the device associated with handle. + + handle:= >=0 (as returned by a prior call to serial_open). + data:= the bytes to write. + + ... + pi.serial_write(h1, b'\\x02\\x03\\x04') + + pi.serial_write(h2, b'help') + + pi.serial_write(h2, "hello") + + pi.serial_write(h1, [2, 3, 4]) + ... + """ + # I p1 handle + # I p2 0 + # I p3 len + ## extension ## + # s len data bytes + + return _u2i(_pigpio_command_ext( + self._control, _PI_CMD_SERW, handle, 0, len(data), [data])) + + def serial_data_available(self, handle): + """ + Returns the number of bytes available to be read from the + device associated with handle. + + handle:= >=0 (as returned by a prior call to serial_open). + + ... + rdy = pi.serial_data_available(h1) + + if rdy > 0: + (b, d) = pi.serial_read(h1, rdy) + ... + """ + return _u2i(_pigpio_command(self._control, _PI_CMD_SERDA, handle, 0)) + + def gpio_trigger(self, user_gpio, pulse_len=10, level=1): + """ + Send a trigger pulse to a gpio. The gpio is set to + level for pulse_len microseconds and then reset to not level. + + user_gpio:= 0-31 + pulse_len:= 1-50 + level:= 0-1 + + ... + pi.gpio_trigger(23, 10, 1) + ... + """ + # pigpio message format + + # I p1 user_gpio + # I p2 pulse_len + # I p3 4 + ## extension ## + # I level + extents = [struct.pack("I", level)] + return _u2i(_pigpio_command_ext( + self._control, _PI_CMD_TRIG, user_gpio, pulse_len, 4, extents)) + + def store_script(self, script): + """ + Store a script for later execution. + + script:= the script text as a series of bytes. + + Returns a >=0 script id if OK. + + ... + sid = pi.store_script( + b'tag 0 w 22 1 mils 100 w 22 0 mils 100 dcr p0 jp 0') + ... + """ + # I p1 0 + # I p2 0 + # I p3 len + ## extension ## + # s len data bytes + if len(script): + return _u2i(_pigpio_command_ext( + self._control, _PI_CMD_PROC, 0, 0, len(script), [script])) + else: + return 0 + + def run_script(self, script_id, params=None): + """ + Runs a stored script. + + script_id:= id of stored script. + params:= up to 10 parameters required by the script. + + ... + s = pi.run_script(sid, [par1, par2]) + + s = pi.run_script(sid) + + s = pi.run_script(sid, [1, 2, 3, 4, 5, 6, 7, 8, 9, 10]) + ... + """ + # I p1 script id + # I p2 0 + # I p3 params * 4 (0-10 params) + ## (optional) extension ## + # I[] params + if params is not None: + ext = bytearray() + for p in params: + ext.extend(struct.pack("I", p)) + nump = len(params) + extents = [ext] + else: + nump = 0 + extents = [] + return _u2i(_pigpio_command_ext( + self._control, _PI_CMD_PROCR, script_id, 0, nump*4, extents)) + + def script_status(self, script_id): + """ + Returns the run status of a stored script as well as the + current values of parameters 0 to 9. + + script_id:= id of stored script. + + The run status may be + + . . + PI_SCRIPT_HALTED + PI_SCRIPT_RUNNING + PI_SCRIPT_WAITING + PI_SCRIPT_FAILED + . . + + The return value is a tuple of run status and a list of + the 10 parameters. On error the run status will be negative + and the parameter list will be empty. + + ... + (s, pars) = pi.script_status(sid) + ... + """ + status = _u2i(_pigpio_command(self._control, _PI_CMD_PROCP, script_id, 0)) + if status >= 0: + param = struct.unpack('IIIIIIIIII', self._control.recv(40)) + return status, param + return status, () + + def stop_script(self, script_id): + """ + Stops a running script. + + script_id:= id of stored script. + + ... + status = pi.stop_script(sid) + ... + """ + return _u2i(_pigpio_command(self._control, _PI_CMD_PROCS, script_id, 0)) + + def delete_script(self, script_id): + """ + Deletes a stored script. + + script_id:= id of stored script. + + ... + status = pi.delete_script(sid) + ... + """ + return _u2i(_pigpio_command(self._control, _PI_CMD_PROCD, script_id, 0)) + + def bb_serial_read_open(self, user_gpio, bb_baud): + """ + Opens a gpio for bit bang reading of serial data. + + user_gpio:= 0-31, the gpio to use. + bb_baud:= 300-250000, the baud rate. + + The serial data is held in a cyclic buffer and is read using + bb_serial_read. + + It is the caller's responsibility to read data from the cyclic + buffer in a timely fashion. + + ... + status = pi.bb_serial_read_open(4, 19200) + status = pi.bb_serial_read_open(17, 9600) + ... + """ + return _u2i(_pigpio_command( + self._control, _PI_CMD_SLRO, user_gpio, bb_baud)) + + def bb_serial_read(self, user_gpio): + """ + Returns data from the bit bang serial cyclic buffer. + + user_gpio:= 0-31 (opened in a prior call to bb_serial_read_open) + + The returned value is a tuple of the number of bytes read and a + bytearray containing the bytes. If there was an error the + number of bytes read will be less than zero (and will contain + the error code). + + ... + (count, data) = pi.bb_serial_read(4) + ... + """ + bytes = _u2i(_pigpio_command(self._control, _PI_CMD_SLR, user_gpio, 10000)) + if bytes > 0: + return bytes, self._rxbuf(bytes) + return bytes, "" + + + def bb_serial_read_close(self, user_gpio): + """ + Closes a gpio for bit bang reading of serial data. + + user_gpio:= 0-31 (opened in a prior call to bb_serial_read_open) + + ... + status = pi.bb_serial_read_close(17) + ... + """ + return _u2i(_pigpio_command(self._control, _PI_CMD_SLRC, user_gpio, 0)) + + def callback(self, user_gpio, edge=RISING_EDGE, func=None): + """ + Calls a user supplied function (a callback) whenever the + specified gpio edge is detected. + + user_gpio:= 0-31. + edge:= EITHER_EDGE, RISING_EDGE (default), or FALLING_EDGE. + func:= user supplied callback function. + + If a user callback is not specified a default tally callback is + provided which simply counts edges. + + The user supplied callback receives three parameters, the gpio, + the level, and the tick. + + ... + def cbf(gpio, level, tick): + print(gpio, level, tick) + + cb1 = pi.callback(22, pigpio.EITHER_EDGE, cbf) + + cb2 = pi.callback(4, pigpio.EITHER_EDGE) + + cb3 = pi.callback(17) + + print(cb3.tally()) + ... + """ + return _callback(self._notify, user_gpio, edge, func) + + def wait_for_edge(self, user_gpio, edge=RISING_EDGE, wait_timeout=60.0): + """ + Wait for an edge event on a gpio. + + user_gpio:= 0-31. + edge:= EITHER_EDGE, RISING_EDGE (default), or + FALLING_EDGE. + wait_timeout:= 0.0- (default 60.0). + + The function returns as soon as the edge is detected + or after the number of seconds specified by timeout has + expired. + + The function returns True if the edge is detected, + otherwise False. + + ... + if pi.wait_for_edge(23): + print("Rising edge detected") + else: + print("wait for edge timed out") + + if pi.wait_for_edge(23, pigpio.FALLING_EDGE, 5.0): + print("Falling edge detected") + else: + print("wait for falling edge timed out") + ... + """ + a = _wait_for_edge(self._notify, user_gpio, edge, wait_timeout) + return a.trigger + + def __init__(self, + host = os.getenv("PIGPIO_ADDR", ''), + port = os.getenv("PIGPIO_PORT", 8888)): + """ + Grants access to a Pi's gpios. + + host:= the host name of the Pi on which the pigpio daemon is + running. The default is localhost unless overwritten by + the PIGPIO_ADDR environment variable. + + port:= the port number on which the pigpio daemon is listening. + The default is 8888 unless overwritten by the PIGPIO_PORT + environment variable. The pigpio daemon must have been + started with the same port number. + + This connects to the pigpio daemon and reserves resources + to be used for sending commands and receiving notifications. + + ... + pi = pigio.pi() # use defaults + pi = pigpio.pi('mypi') # specify host, default port + pi = pigpio.pi('mypi', 7777) # specify host and port + ... + """ + self.connected = True + + self._control = None + self._notify = None + + self._host = '' + self._port = 8888 + + self._host = host + self._port = int(port) + + self._control = socket.socket(socket.AF_INET, socket.SOCK_STREAM) + + try: + self._control.connect((self._host, self._port)) + self._notify = _callback_thread(self._control, self._host, self._port) + except socket.error: + self.connected = False + if self._control is not None: + self._control = None + if self._host == '': + h = "localhost" + else: + h = self._host + errStr = "Can't connect to pigpio on " + str(h) + "(" + str(self._port) + ")" + print("%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%") + print(errStr) + print("") + print("Did you start the pigpio daemon? E.g. sudo pigpiod") + print("") + print("Did you specify the correct Pi host/port in the environment") + print("variables PIGPIO_ADDR/PIGPIO_PORT?") + print("E.g. export PIGPIO_ADDR=soft, export PIGPIO_PORT=8888") + print("") + print("Did you specify the correct Pi host/port in the") + print("pigpio.pi() function? E.g. pigpio.pi('soft', 8888))") + print("%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%") + else: + atexit.register(self.stop) + + def stop(self): + """Release pigpio resources. + + ... + pi.stop() + ... + """ + + if self._notify is not None: + self._notify.stop() + self._notify = None + + if self._control is not None: + self._control.close() + self._control = None + +def variables(): """ - global _control, _notify + bb_baud: 100 - 250000 + The baud rate used for the transmission of bit bang serial data. - if _notify is not None: - _notify.stop() - _notify = None + bit: 0-1 + A value of 0 or 1. - if _control is not None: - _control.close() - _control = None + bits: 32 bit number + A mask used to select gpios to be operated on. If bit n is set + then gpio n is selected. A convenient way of setting bit n is to + bit or in the value (1< 0) + { + /* get the data */ + recv(gPigCommand, buf, bytes, MSG_WAITALL); + } + return bytes; +} + +int i2c_write_device(unsigned handle, char *buf, unsigned count) +{ + gpioExtent_t ext[1]; + + /* + p1=handle + p2=0 + p3=count + ## extension ## + char buf[count] flags + */ + + ext[0].size = count; + ext[0].ptr = buf; + + return pigpio_command_ext + (gPigCommand, PI_CMD_I2CWD, handle, 0, count, 1, ext); +} + +int i2c_write_quick(unsigned handle, unsigned bit) + {return pigpio_command(gPigCommand, PI_CMD_I2CWQ, handle, bit);} + +int i2c_write_byte(unsigned handle, unsigned val) + {return pigpio_command(gPigCommand, PI_CMD_I2CWS, handle, val);} + +int i2c_read_byte(unsigned handle) + {return pigpio_command(gPigCommand, PI_CMD_I2CRS, handle, 0);} + +int i2c_write_byte_data(unsigned handle, unsigned reg, unsigned val) +{ + gpioExtent_t ext[1]; + + /* + p1=handle + p2=reg + p3=4 + ## extension ## + uint32_t val + */ + + ext[0].size = 4; + ext[0].ptr = &val; + + return pigpio_command_ext + (gPigCommand, PI_CMD_I2CWB, handle, reg, 4, 1, ext); +} + +int i2c_write_word_data(unsigned handle, unsigned reg, unsigned val) +{ + gpioExtent_t ext[1]; + + /* + p1=handle + p2=reg + p3=4 + ## extension ## + uint32_t val + */ + + ext[0].size = 4; + ext[0].ptr = &val; + + return pigpio_command_ext + (gPigCommand, PI_CMD_I2CWW, handle, reg, 4, 1, ext); +} + +int i2c_read_byte_data(unsigned handle, unsigned reg) + {return pigpio_command(gPigCommand, PI_CMD_I2CRB, handle, reg);} + +int i2c_read_word_data(unsigned handle, unsigned reg) + {return pigpio_command(gPigCommand, PI_CMD_I2CRW, handle, reg);} + +int i2c_process_call(unsigned handle, unsigned reg, unsigned val) +{ + gpioExtent_t ext[1]; + + /* + p1=handle + p2=reg + p3=4 + ## extension ## + uint32_t val + */ + + ext[0].size = 4; + ext[0].ptr = &val; + + return pigpio_command_ext + (gPigCommand, PI_CMD_I2CPK, handle, reg, 4, 1, ext); +} + +int i2c_write_block_data( + unsigned handle, unsigned reg, char *buf, unsigned count) +{ + gpioExtent_t ext[1]; + + /* + p1=handle + p2=reg + p3=count + ## extension ## + char buf[count] + */ + + ext[0].size = count; + ext[0].ptr = buf; + + return pigpio_command_ext + (gPigCommand, PI_CMD_I2CWK, handle, reg, count, 1, ext); +} + +int i2c_read_block_data(unsigned handle, unsigned reg, char *buf) +{ + int bytes; + + bytes = pigpio_command(gPigCommand, PI_CMD_I2CRK, handle, reg); + + if (bytes > 0) + { + /* get the data */ + recv(gPigCommand, buf, bytes, MSG_WAITALL); + } + return bytes; +} + +int i2c_block_process_call( + unsigned handle, unsigned reg, char *buf, unsigned count) +{ + int bytes; + gpioExtent_t ext[1]; + + /* + p1=handle + p2=reg + p3=count + ## extension ## + char buf[count] + */ + + ext[0].size = count; + ext[0].ptr = buf; + + bytes = pigpio_command_ext + (gPigCommand, PI_CMD_I2CPK, handle, reg, count, 1, ext); + + if (bytes > 0) + { + /* get the data */ + recv(gPigCommand, buf, bytes, MSG_WAITALL); + } + return bytes; +} + +int i2c_read_i2c_block_data( + unsigned handle, unsigned reg, char *buf, unsigned count) +{ + int bytes; + gpioExtent_t ext[1]; + + /* + p1=handle + p2=reg + p3=4 + ## extension ## + uint32_t count + */ + + ext[0].size = 4; + ext[0].ptr = &count; + + bytes = pigpio_command_ext + (gPigCommand, PI_CMD_I2CRI, handle, reg, 4, 1, ext); + + if (bytes > 0) + { + /* get the data */ + recv(gPigCommand, buf, bytes, MSG_WAITALL); + } + return bytes; +} + + +int i2c_write_i2c_block_data( + unsigned handle, unsigned reg, char *buf, unsigned count) +{ + gpioExtent_t ext[1]; + + /* + p1=handle + p2=reg + p3=count + ## extension ## + char buf[count] + */ + + ext[0].size = count; + ext[0].ptr = buf; + + return pigpio_command_ext + (gPigCommand, PI_CMD_I2CWI, handle, reg, count, 1, ext); +} + +int spi_open(unsigned channel, unsigned speed, unsigned flags) +{ + gpioExtent_t ext[1]; + + /* + p1=channel + p2=speed + p3=4 + ## extension ## + uint32_t flags + */ + + ext[0].size = 4; + ext[0].ptr = &flags; + + return pigpio_command_ext + (gPigCommand, PI_CMD_SPIO, channel, speed, 4, 1, ext); +} + +int spi_close(unsigned handle) + {return pigpio_command(gPigCommand, PI_CMD_SPIC, handle, 0);} + +int spi_read(unsigned handle, char *buf, unsigned count) +{ + int bytes; + + bytes = pigpio_command + (gPigCommand, PI_CMD_SPIR, handle, count); + + if (bytes > 0) + { + /* get the data */ + recv(gPigCommand, buf, bytes, MSG_WAITALL); + } + return bytes; +} + +int spi_write(unsigned handle, char *buf, unsigned count) +{ + gpioExtent_t ext[1]; + + /* + p1=handle + p2=0 + p3=count + ## extension ## + char buf[count] + */ + + ext[0].size = count; + ext[0].ptr = buf; + + return pigpio_command_ext + (gPigCommand, PI_CMD_SPIW, handle, 0, count, 1, ext); +} + +int spi_xfer(unsigned handle, char *txBuf, char *rxBuf, unsigned count) +{ + int bytes; + gpioExtent_t ext[1]; + + /* + p1=handle + p2=0 + p3=count + ## extension ## + char buf[count] + */ + + ext[0].size = count; + ext[0].ptr = txBuf; + + bytes = pigpio_command_ext + (gPigCommand, PI_CMD_SPIX, handle, 0, count, 1, ext); + + if (bytes > 0) + { + /* get the data */ + recv(gPigCommand, rxBuf, bytes, MSG_WAITALL); + } + return bytes; +} + +int serial_open(char *dev, unsigned baud, unsigned flags) +{ + int len; + gpioExtent_t ext[1]; + + len = strlen(dev); + + /* + p1=baud + p2=flags + p3=len + ## extension ## + char dev[len] + */ + + ext[0].size = len; + ext[0].ptr = dev; + + return pigpio_command_ext + (gPigCommand, PI_CMD_SERO, baud, flags, len, 1, ext); +} + +int serial_close(unsigned handle) + {return pigpio_command(gPigCommand, PI_CMD_SERC, handle, 0);} + +int serial_write_byte(unsigned handle, unsigned val) + {return pigpio_command(gPigCommand, PI_CMD_SERWB, handle, val);} + +int serial_read_byte(unsigned handle) + {return pigpio_command(gPigCommand, PI_CMD_SERRB, handle, 0);} + +int serial_write(unsigned handle, char *buf, unsigned count) +{ + gpioExtent_t ext[1]; + + /* + p1=handle + p2=0 + p3=count + ## extension ## + char buf[count] + */ + + ext[0].size = count; + ext[0].ptr = buf; + + return pigpio_command_ext + (gPigCommand, PI_CMD_SERW, handle, 0, count, 1, ext); +} + +int serial_read(unsigned handle, char *buf, unsigned count) +{ + int bytes; + + bytes = pigpio_command + (gPigCommand, PI_CMD_SERR, handle, count); + + if (bytes > 0) + { + /* get the data */ + recv(gPigCommand, buf, bytes, MSG_WAITALL); + } + return bytes; +} + +int serial_data_available(unsigned handle) + {return pigpio_command(gPigCommand, PI_CMD_SERDA, handle, 0);} + int callback(unsigned gpio, unsigned edge, CBFunc_t f) {return intCallback(gpio, edge, f, 0, 0);} diff --git a/pigpiod_if.h b/pigpiod_if.h index ef01ca8..81b4b79 100644 --- a/pigpiod_if.h +++ b/pigpiod_if.h @@ -762,33 +762,221 @@ int delete_script(unsigned script_id); The function returns 0 if OK, otherwise PI_BAD_SCRIPT_ID. */ -int serial_read_open(unsigned user_gpio, unsigned baud); -/* This function opens a gpio for reading serial data. +int bb_serial_read_open(unsigned user_gpio, unsigned baud); +/* This function opens a gpio for bit-banged reading of serial data. Returns 0 if OK, otherwise PI_BAD_USER_GPIO, PI_BAD_WAVE_BAUD, or PI_GPIO_IN_USE. The serial data is returned in a cyclic buffer and is read using - serial_read(). + bb_serial_read(). It is the caller's responsibility to read data from the cyclic buffer in a timely fashion. */ -int serial_read(unsigned user_gpio, void *buf, size_t bufSize); +int bb_serial_read(unsigned user_gpio, void *buf, size_t bufSize); /* This function copies up to bufSize bytes of data read from the - serial cyclic buffer to the buffer starting at buf. + bit-bang serial cyclic buffer to the buffer starting at buf. Returns the number of bytes copied if OK, otherwise PI_BAD_USER_GPIO or PI_NOT_SERIAL_GPIO. */ -int serial_read_close(unsigned user_gpio); -/* This function closes a gpio for reading serial data. +int bb_serial_read_close(unsigned user_gpio); +/* This function closes a gpio for bit-banged reading of serial data. Returns 0 if OK, otherwise PI_BAD_USER_GPIO, or PI_NOT_SERIAL_GPIO. */ +int i2c_open(unsigned bus, unsigned addr, unsigned flags); +/* This returns a handle for the device at address addr on I2C bus bus. + + No flags are currently defined. This parameter should be set to zero. +*/ + +int i2c_close(unsigned handle); +/* This closes the I2C device associated with the handle. +*/ + +int i2c_read_device(unsigned handle, char *buf, unsigned count); +/* This reads count bytes from the raw device into buf. +*/ + +int i2c_write_device(unsigned handle, char *buf, unsigned count); +/* This writes count bytes from buf to the raw device. +*/ + +int i2c_write_quick(unsigned handle, unsigned bit); +/* This sends a single bit to the device (in the Rd/Wr bit). + + Quick command. smbus 2.0 5.5.1 +*/ + +int i2c_write_byte(unsigned handle, unsigned val); +/* This operation is the reverse of i2cReadByte: it sends a single byte + to a device. + + Send byte. smbus 2.0 5.5.2 +*/ + +int i2c_read_byte(unsigned handle); +/* This reads a single byte from a device, without specifying a device + register. Some devices are so simple that this interface is enough; + for others, it is a shorthand if you want to read the same register + as in the previous SMBus command. + + Receive byte. smbus 2.0 5.5.3 +*/ + +int i2c_write_byte_data(unsigned handle, unsigned reg, unsigned val); +/* This writes a single byte to a device, to a designated register. + This is the opposite of the i2cReadByte function. + + Write byte. smbus 2.0 5.5.4 +*/ + +int i2c_write_word_data(unsigned handle, unsigned reg, unsigned val); +/* This is the opposite of the i2cReadWordData operation. 16 bits + of data is written to a device, to the designated register. + + Write word. smbus 2.0 5.5.4 +*/ + +int i2c_read_byte_data(unsigned handle, unsigned reg); +/* This reads a single byte from a device, from a designated register. + + Read byte. smbus 2.0 5.5.5 +*/ + +int i2c_read_word_data(unsigned handle, unsigned reg); +/* This operation is very like i2cReadByte; again, data is read + from a device, from a designated register. But this time, the data + is a complete word (16 bits). + + Read word. smbus 2.0 5.5.5 +*/ + +int i2c_process_call(unsigned handle, unsigned reg, unsigned val); +/* This command selects a device register, sends 16 bits of data to it, + and reads 16 bits of data in return. + + Process call. smbus 2.0 5.5.6 +*/ + +int i2c_write_block_data( + unsigned handle, unsigned reg, char *buf, unsigned count); +/* The opposite of the i2cReadBlockData command, this writes up to + 32 bytes to a device, to a designated register. The amount of data + is specified in the count byte. + + Block write. smbus 2.0 5.5.7 +*/ + +int i2c_read_block_data(unsigned handle, unsigned reg, char *buf); +/* This command reads a block of up to 32 bytes from a device, from a + designated register. The amount of returned data is set by the device. + + Block read. smbus 2.0 5.5.7 +*/ + +int i2c_block_process_call( + unsigned handle, unsigned reg, char *buf, unsigned count); +/* This command selects a device register, sends count bytes of data + to it, and reads a device specified number of bytes of data in return. + + The smbus 2.0 documentation states that a minimum of 1 byte may be + sent and a minimum of 1 byte may be received. The total number of + bytes sent/received must be 32 or less. + + Block write-block read. smbus 2.0 5.5.8 +*/ + +int i2c_read_i2c_block_data( + unsigned handle, unsigned reg, char *buf, unsigned count); +/* This command reads a block of bytes from a device, from a + designated register. The count may be 1-32. +*/ + + +int i2c_write_i2c_block_data( + unsigned handle, unsigned reg, char *buf, unsigned count); +/* The opposite of the i2cReadI2CBlockData command, this writes bytes to + a device, to a designated register.. Note that command lengths of 0, 2, + or more bytes are supported as they are indistinguishable from data. + Count may be 1-32. +*/ + +int spi_open(unsigned channel, unsigned speed, unsigned flags); +/* This function returns a handle for the SPI device on channel. + Data will be transferred at speed bits per second. + + The bottom two bits of flags define the SPI mode as follows. + bit bit + 1 0 + Mode POL PHA + 0 0 0 + 1 0 1 + 2 1 0 + 3 1 1 + + The other bits in flags should be set to zero. +*/ + +int spi_close(unsigned handle); +/* This functions closes the SPI device identified by the handle. +*/ + +int spi_read(unsigned handle, char *buf, unsigned count); +/* This function reads count bytes of data from the SPI + device associated with the handle. +*/ + +int spi_write(unsigned handle, char *buf, unsigned count); +/* This function writes count bytes of data from buf to the SPI + device associated with the handle. +*/ + +int spi_xfer(unsigned handle, char *txBuf, char *rxBuf, unsigned count); +/* This function writes count bytes of data from txBuf to the SPI + device associated with the handle. + + The data read from the device is written to rxBuf. +*/ + +int serial_open(char *dev, unsigned baud, unsigned flags); +/* This function open the serial device named dev at baud bits per second. + + No flags are currently defined. This parameter should be set to zero. +*/ + +int serial_close(unsigned handle); +/* This function closes the serial device associated with handle. +*/ + +int serial_write_byte(unsigned handle, unsigned val); +/* This function writes val to the serial port associated with handle. +*/ + +int serial_read_byte(unsigned handle); +/* This function reads a byte from the serial port associated with handle. +*/ + +int serial_write(unsigned handle, char *buf, unsigned count); +/* This function writes count bytes from buf to the the serial port + associated with handle. +*/ + +int serial_read(unsigned handle, char *buf, unsigned count); +/* This function reads count bytes from the the serial port + associated with handle and writes them to buf. +*/ + +int serial_data_available(unsigned handle); +/* Returns the number of bytes available to be read from the + device associated with handle. +*/ + int callback(unsigned gpio, unsigned edge, CBFunc_t f); /* This function initialises a new callback. diff --git a/pigs.c b/pigs.c index 3cce611..5d9806a 100644 --- a/pigs.c +++ b/pigs.c @@ -26,7 +26,7 @@ For more information, please refer to */ /* -This version is for pigpio version 14+ +This version is for pigpio version 16+ */ #include @@ -142,11 +142,11 @@ void print_result(int sock, int rv, cmdCmd_t cmd) printf(cmdUsage); break; - case 6: /* SLR */ + case 6: /* SLR I2CRD */ if (r < 0) fatal("ERROR: %s", cmdErrStr(r)); else if (r > 0) { - printf("%s", response_buf); + write(1, response_buf, r); } break; @@ -173,7 +173,7 @@ void get_extensions(int sock, int command, int res) { switch (command) { - case PI_CMD_PROCP: /* PROCP */ + case PI_CMD_PROCP: if (res >= 0) { recv(sock, @@ -183,7 +183,15 @@ void get_extensions(int sock, int command, int res) } break; - case PI_CMD_SLR: /* SLR */ + case PI_CMD_I2CPK: + case PI_CMD_I2CRD: + case PI_CMD_I2CRI: + case PI_CMD_I2CRK: + case PI_CMD_SERR: + case PI_CMD_SLR: + case PI_CMD_SPIX: + case PI_CMD_SPIR: + if (res > 0) { recv(sock, response_buf, res, MSG_WAITALL); @@ -193,76 +201,15 @@ void get_extensions(int sock, int command, int res) } } -void put_extensions(int sock, int command, uint32_t *p, void *v[]) -{ - switch (command) - { - case PI_CMD_PROC: - /* - p1=script length w[1] - p2=0 - ## extension ## - char[] script v[1] - */ - send(sock, v[1], p[1], 0); - break; - - case PI_CMD_PROCR: - /* - p1=script id w[1] - p2=numParam w[2] - ## extension ## - int[] param v[1] - */ - if (p[2]) send(sock, v[1], p[2]*sizeof(uint32_t), 0); - break; - - case PI_CMD_TRIG: - /* - p1=user_gpio w[1] - p2=pulseLen w[2] - ## extension ## - unsigned level w[3] - */ - send(sock, &p[3], 4, 0); - break; - - case PI_CMD_WVAG: - /* - p1=pulses w[1] - p2=0 - ## extension ## - int[] param v[1] - */ - if (p[1]) send(sock, v[1], p[1]*sizeof(gpioPulse_t), 0); - break; - - case PI_CMD_WVAS: - /* - p1=user_gpio w[1] - p2=numChar w[4] - ## extension ## - unsigned baud w[2] - unsigned offset w[3] - char[] str v[1] - */ - send(sock, &p[2], 4, 0); - send(sock, &p[3], 4, 0); - send(sock, v[1], p[4], 0); - break; - } - -} - int main(int argc , char *argv[]) { int sock, command; int idx, i, pp, l, len; cmdCmd_t cmd; - uint32_t p[10]; - void *v[10]; + uint32_t p[CMD_P_ARR]; cmdCtlParse_t ctl; cmdScript_t s; + char v[CMD_MAX_EXTENSION]; sock = openSocket(); @@ -286,7 +233,7 @@ int main(int argc , char *argv[]) while ((idx >= 0) && (ctl.eaten < len)) { - if ((idx=cmdParse(command_buf, p, v, &ctl)) >= 0) + if ((idx=cmdParse(command_buf, p, CMD_MAX_EXTENSION, v, &ctl)) >= 0) { command = p[0]; @@ -298,7 +245,7 @@ int main(int argc , char *argv[]) } else if (command == PI_CMD_PARSE) { - cmdParseScript(v[1], &s, 1); + cmdParseScript(v, &s, 1); if (s.par) free (s.par); } else @@ -306,24 +253,14 @@ int main(int argc , char *argv[]) cmd.cmd = command; cmd.p1 = p[1]; cmd.p2 = p[2]; - - switch (command) - { - case PI_CMD_WVAS: - cmd.p2 = p[4]; - break; - - case PI_CMD_PROC: - cmd.p2 = 0; - break; - } + cmd.p3 = p[3]; if (sock != SOCKET_OPEN_FAILED) { if (send(sock, &cmd, sizeof(cmdCmd_t), 0) == sizeof(cmdCmd_t)) { - put_extensions(sock, command, p, v); + if (p[3]) send(sock, v, p[3], 0); /* send extensions */ if (recv(sock, &cmd, sizeof(cmdCmd_t), MSG_WAITALL) == sizeof(cmdCmd_t)) @@ -332,11 +269,11 @@ int main(int argc , char *argv[]) print_result(sock, cmdInfo[idx].rv, cmd); } - else fatal("recv failed, %m"); + else fatal("socket receive failed"); } - else fatal("send failed, %m"); + else fatal("socket send failed"); } - else fatal("connect failed"); + else fatal("socket connect failed"); } } else fatal("%s only allowed within a script", cmdInfo[idx].name); diff --git a/setup.py b/setup.py index 14465f1..00cd6c7 100644 --- a/setup.py +++ b/setup.py @@ -3,7 +3,7 @@ from distutils.core import setup setup(name='pigpio', - version='1.5', + version='1.6', author='joan', author_email='joan@abyz.co.uk', maintainer='joan', diff --git a/x_pigpio.c b/x_pigpio.c index c827a7b..b12092d 100644 --- a/x_pigpio.c +++ b/x_pigpio.c @@ -17,6 +17,7 @@ sudo ./x_pigpio #include #include #include +#include #include "pigpio.h" @@ -623,10 +624,214 @@ void t9() CHECK(9, 4, e, 0, 0, "delete script"); } +void ta() +{ + int h, b, e; + char *TEXT; + char text[2048]; + + printf("Serial link tests.\n"); + + /* this test needs RXD and TXD to be connected */ + + h = serOpen("/dev/ttyAMA0", 57600, 0); + + CHECK(10, 1, h, 0, 0, "serial open"); + + b = serRead(h, text, sizeof(text)); /* flush buffer */ + + b = serDataAvailable(h); + CHECK(10, 2, b, 0, 0, "serial data available"); + + TEXT = "\ +To be, or not to be, that is the question-\ +Whether 'tis Nobler in the mind to suffer\ +The Slings and Arrows of outrageous Fortune,\ +Or to take Arms against a Sea of troubles,\ +"; + e = serWrite(h, TEXT, strlen(TEXT)); + CHECK(10, 3, e, 0, 0, "serial write"); + + e = serWriteByte(h, 0xAA); + e = serWriteByte(h, 0x55); + e = serWriteByte(h, 0x00); + e = serWriteByte(h, 0xFF); + + CHECK(10, 4, e, 0, 0, "serial write byte"); + + time_sleep(0.1); /* allow time for transmission */ + + b = serDataAvailable(h); + CHECK(10, 5, b, strlen(TEXT)+4, 0, "serial data available"); + + b = serRead(h, text, strlen(TEXT)); + CHECK(10, 6, b, strlen(TEXT), 0, "serial read"); + if (b >= 0) text[b] = 0; + CHECK(10, 7, strcmp(TEXT, text), 0, 0, "serial read"); + + b = serReadByte(h); + CHECK(10, 8, b, 0xAA, 0, "serial read byte"); + + b = serReadByte(h); + CHECK(10, 9, b, 0x55, 0, "serial read byte"); + + b = serReadByte(h); + CHECK(10, 10, b, 0x00, 0, "serial read byte"); + + b = serReadByte(h); + CHECK(10, 11, b, 0xFF, 0, "serial read byte"); + + b = serDataAvailable(h); + CHECK(10, 12, b, 0, 0, "serial data availabe"); + + e = serClose(h); + CHECK(10, 13, e, 0, 0, "serial close"); +} + +void tb() +{ + int h, e, b, len; + char *exp; + char buf[128]; + + printf("SMBus / I2C tests."); + + /* this test requires an ADXL345 on I2C bus 1 addr 0x53 */ + + h = i2cOpen(1, 0x53, 0); + CHECK(11, 1, h, 0, 0, "i2cOpen"); + + e = i2cWriteDevice(h, "\x00", 1); /* move to known register */ + CHECK(11, 2, e, 0, 0, "i2cWriteDevice"); + + b = i2cReadDevice(h, buf, 1); + CHECK(11, 3, b, 1, 0, "i2cReadDevice"); + CHECK(11, 4, buf[0], 0xE5, 0, "i2cReadDevice"); + + b = i2cReadByte(h); + CHECK(11, 5, b, 0xE5, 0, "i2cReadByte"); + + b = i2cReadByteData(h, 0); + CHECK(11, 6, b, 0xE5, 0, "i2cReadByteData"); + + b = i2cReadByteData(h, 48); + CHECK(11, 7, b, 2, 0, "i2cReadByteData"); + + exp = "\x1D[aBcDeFgHjKM]"; + len = strlen(exp); + + e = i2cWriteDevice(h, exp, len); + CHECK(11, 8, e, 0, 0, "i2cWriteDevice"); + + e = i2cWriteDevice(h, "\x1D", 1); + b = i2cReadDevice(h, buf, len-1); + CHECK(11, 9, b, len-1, 0, "i2cReadDevice"); + CHECK(11, 10, strncmp(buf, exp+1, len-1), 0, 0, "i2cReadDevice"); + + if (strncmp(buf, exp+1, len-1)) + printf("got [%.*s] expected [%.*s]\n", len-1, buf, len-1, exp+1); + + e = i2cWriteByteData(h, 0x1d, 0xAA); + CHECK(11, 11, e, 0, 0, "i2cWriteByteData"); + + b = i2cReadByteData(h, 0x1d); + CHECK(11, 12, b, 0xAA, 0, "i2cReadByteData"); + + e = i2cWriteByteData(h, 0x1d, 0x55); + CHECK(11, 13, e, 0, 0, "i2cWriteByteData"); + + b = i2cReadByteData(h, 0x1d); + CHECK(11, 14, b, 0x55, 0, "i2cReadByteData"); + + exp = "[1234567890#]"; + len = strlen(exp); + + e = i2cWriteBlockData(h, 0x1C, exp, len); + CHECK(11, 15, e, 0, 0, "i2c writeBlockData"); + + e = i2cWriteDevice(h, "\x1D", 1); + b = i2cReadDevice(h, buf, len); + CHECK(11, 16, b, len, 0, "i2cReadDevice"); + CHECK(11, 17, strncmp(buf, exp, len), 0, 0, "i2cReadDevice"); + + if (strncmp(buf, exp, len)) + printf("got [%.*s] expected [%.*s]\n", len, buf, len, exp); + + b = i2cReadI2CBlockData(h, 0x1D, buf, len); + CHECK(11, 18, b, len, 0, "i2cReadI2CBlockData"); + CHECK(11, 19, strncmp(buf, exp, len), 0, 0, "i2cReadI2CBlockData"); + + if (strncmp(buf, exp, len)) + printf("got [%.*s] expected [%.*s]\n", len, buf, len, exp); + + exp = "(-+=;:,<>!%)"; + len = strlen(exp); + + e = i2cWriteI2CBlockData(h, 0x1D, exp, len); + CHECK(11, 20, e, 0, 0, "i2cWriteI2CBlockData"); + + b = i2cReadI2CBlockData(h, 0x1D, buf, len); + CHECK(11, 21, b, len, 0, "i2cReadI2CBlockData"); + CHECK(11, 22, strncmp(buf, exp, len), 0, 0, "i2cReadI2CBlockData"); + + if (strncmp(buf, exp, len)) + printf("got [%.*s] expected [%.*s]\n", len, buf, len, exp); + + e = i2cClose(h); + CHECK(11, 23, e, 0, 0, "i2cClose"); +} + +void tc() +{ + int h, x, b, e; + char txBuf[8], rxBuf[8]; + + printf("SPI tests."); + + /* this test requires a MCP3202 on SPI channel 1 */ + + h = spiOpen(1, 50000, 0); + CHECK(12, 1, h, 0, 0, "spiOpen"); + + sprintf(txBuf, "\x01\x80"); + + for (x=0; x<5; x++) + { + b = spiXfer(h, txBuf, rxBuf, 3); + CHECK(12, 2, b, 3, 0, "spiXfer"); + if (b == 3) + { + time_sleep(1.0); + printf("%d ", ((rxBuf[1]&0x0F)*256)|rxBuf[2]); + } + } + + e = spiClose(h); + CHECK(12, 99, e, 0, 0, "spiClose"); +} + int main(int argc, char *argv[]) { - int t, status; - void (*test[])(void) = {t0, t1, t2, t3, t4, t5, t6, t7, t8, t9}; + int i, t, c, status; + + char test[64]; + + if (argc > 1) + { + t = 0; + + for (i=0; i= (((1E2-pc)*expect)/1E2) and got <= (((1E2+pc)*expect)/1E2): print("TEST {:2d}.{:<2d} PASS ({}: {:d})".format(t, st, desc, expect)) @@ -22,37 +31,38 @@ def CHECK(t, st, got, expect, pc, desc): format(t, st, got, desc, expect)) def t0(): + print("Version.") - print("pigpio version {}.".format(pigpio.get_pigpio_version())) + print("pigpio version {}.".format(pi.get_pigpio_version())) - print("Hardware revision {}.".format(pigpio.get_hardware_revision())) + print("Hardware revision {}.".format(pi.get_hardware_revision())) def t1(): print("Mode/PUD/read/write tests.") - pigpio.set_mode(GPIO, pigpio.INPUT) - v = pigpio.get_mode(GPIO) + pi.set_mode(GPIO, pigpio.INPUT) + v = pi.get_mode(GPIO) CHECK(1, 1, v, 0, 0, "set mode, get mode") - pigpio.set_pull_up_down(GPIO, pigpio.PUD_UP) - v = pigpio.read(GPIO) + pi.set_pull_up_down(GPIO, pigpio.PUD_UP) + v = pi.read(GPIO) CHECK(1, 2, v, 1, 0, "set pull up down, read") - pigpio.set_pull_up_down(GPIO, pigpio.PUD_DOWN) - v = pigpio.read(GPIO) + pi.set_pull_up_down(GPIO, pigpio.PUD_DOWN) + v = pi.read(GPIO) CHECK(1, 3, v, 0, 0, "set pull up down, read") - pigpio.write(GPIO, pigpio.LOW) - v = pigpio.get_mode(GPIO) + pi.write(GPIO, pigpio.LOW) + v = pi.get_mode(GPIO) CHECK(1, 4, v, 1, 0, "write, get mode") - v = pigpio.read(GPIO) + v = pi.read(GPIO) CHECK(1, 5, v, 0, 0, "read") - pigpio.write(GPIO, pigpio.HIGH) - v = pigpio.read(GPIO) + pi.write(GPIO, pigpio.HIGH) + v = pi.read(GPIO) CHECK(1, 6, v, 1, 0, "write, read") t2_count=0 @@ -62,33 +72,34 @@ def t2cbf(gpio, level, tick): t2_count += 1 def t2(): + global t2_count print("PWM dutycycle/range/frequency tests.") - pigpio.set_PWM_range(GPIO, 255) - pigpio.set_PWM_frequency(GPIO,0) - f = pigpio.get_PWM_frequency(GPIO) + pi.set_PWM_range(GPIO, 255) + pi.set_PWM_frequency(GPIO,0) + f = pi.get_PWM_frequency(GPIO) CHECK(2, 1, f, 10, 0, "set PWM range, set/get PWM frequency") - t2cb = pigpio.callback(GPIO, pigpio.EITHER_EDGE, t2cbf) + t2cb = pi.callback(GPIO, pigpio.EITHER_EDGE, t2cbf) - pigpio.set_PWM_dutycycle(GPIO, 0) + pi.set_PWM_dutycycle(GPIO, 0) time.sleep(0.5) # allow old notifications to flush oc = t2_count time.sleep(2) f = t2_count - oc CHECK(2, 2, f, 0, 0, "set PWM dutycycle, callback") - pigpio.set_PWM_dutycycle(GPIO, 128) + pi.set_PWM_dutycycle(GPIO, 128) time.sleep(1) oc = t2_count time.sleep(2) f = t2_count - oc CHECK(2, 3, f, 40, 5, "set PWM dutycycle, callback") - pigpio.set_PWM_frequency(GPIO,100) - f = pigpio.get_PWM_frequency(GPIO) + pi.set_PWM_frequency(GPIO,100) + f = pi.get_PWM_frequency(GPIO) CHECK(2, 4, f, 100, 0, "set/get PWM frequency") time.sleep(1) @@ -97,8 +108,8 @@ def t2(): f = t2_count - oc CHECK(2, 5, f, 400, 1, "callback") - pigpio.set_PWM_frequency(GPIO,1000) - f = pigpio.get_PWM_frequency(GPIO) + pi.set_PWM_frequency(GPIO,1000) + f = pi.get_PWM_frequency(GPIO) CHECK(2, 6, f, 1000, 0, "set/get PWM frequency") time.sleep(1) @@ -107,20 +118,20 @@ def t2(): f = t2_count - oc CHECK(2, 7, f, 4000, 1, "callback") - r = pigpio.get_PWM_range(GPIO) + r = pi.get_PWM_range(GPIO) CHECK(2, 8, r, 255, 0, "get PWM range") - rr = pigpio.get_PWM_real_range(GPIO) + rr = pi.get_PWM_real_range(GPIO) CHECK(2, 9, rr, 200, 0, "get PWM real range") - pigpio.set_PWM_range(GPIO, 2000) - r = pigpio.get_PWM_range(GPIO) + pi.set_PWM_range(GPIO, 2000) + r = pi.get_PWM_range(GPIO) CHECK(2, 10, r, 2000, 0, "set/get PWM range") - rr = pigpio.get_PWM_real_range(GPIO) + rr = pi.get_PWM_real_range(GPIO) CHECK(2, 11, rr, 200, 0, "get PWM real range") - pigpio.set_PWM_dutycycle(GPIO, 0) + pi.set_PWM_dutycycle(GPIO, 0) t3_reset=True t3_count=0 @@ -148,6 +159,7 @@ def t3cbf(gpio, level, tick): t3_tick = tick def t3(): + global t3_reset, t3_count, t3_on, t3_off pw=[500.0, 1500.0, 2500.0] @@ -155,12 +167,12 @@ def t3(): print("PWM/Servo pulse accuracy tests.") - t3cb = pigpio.callback(GPIO, pigpio.EITHER_EDGE, t3cbf) + t3cb = pi.callback(GPIO, pigpio.EITHER_EDGE, t3cbf) t = 0 for x in pw: t += 1 - pigpio.set_servo_pulsewidth(GPIO, x) + pi.set_servo_pulsewidth(GPIO, x) time.sleep(1) t3_reset = True time.sleep(4) @@ -170,18 +182,18 @@ def t3(): CHECK(3, t, int((1E3*(on+off))/on), int(2E7/x), 1, "set servo pulsewidth") - pigpio.set_servo_pulsewidth(GPIO, 0) - pigpio.set_PWM_frequency(GPIO, 1000) - f = pigpio.get_PWM_frequency(GPIO) + pi.set_servo_pulsewidth(GPIO, 0) + pi.set_PWM_frequency(GPIO, 1000) + f = pi.get_PWM_frequency(GPIO) CHECK(3, 4, f, 1000, 0, "set/get PWM frequency") - rr = pigpio.set_PWM_range(GPIO, 100) + rr = pi.set_PWM_range(GPIO, 100) CHECK(3, 5, rr, 200, 0, "set PWM range") t = 5 for x in dc: t += 1 - pigpio.set_PWM_dutycycle(GPIO, x*100) + pi.set_PWM_dutycycle(GPIO, x*100) time.sleep(1) t3_reset = True time.sleep(2) @@ -190,33 +202,38 @@ def t3(): off = t3_off CHECK(3, t, int((1E3*on)/(on+off)), int(1E3*x), 1, "set PWM dutycycle") - pigpio.set_PWM_dutycycle(GPIO, 0) + pi.set_PWM_dutycycle(GPIO, 0) def t4(): print("Pipe notification tests.") - pigpio.set_PWM_frequency(GPIO, 0) - pigpio.set_PWM_dutycycle(GPIO, 0) - pigpio.set_PWM_range(GPIO, 100) + pi.set_PWM_frequency(GPIO, 0) + pi.set_PWM_dutycycle(GPIO, 0) + pi.set_PWM_range(GPIO, 100) - h = pigpio.notify_open() - e = pigpio.notify_begin(h, (1<<4)) + h = pi.notify_open() + e = pi.notify_begin(h, (1<<4)) CHECK(4, 1, e, 0, 0, "notify open/begin") time.sleep(1) - with open("/dev/pigpio"+ str(h), "rb") as f: + try: + f = open("/dev/pigpio"+ str(h), "rb") + except IOError: + f = None - pigpio.set_PWM_dutycycle(GPIO, 50) - time.sleep(4) - pigpio.set_PWM_dutycycle(GPIO, 0) + pi.set_PWM_dutycycle(GPIO, 50) + time.sleep(4) + pi.set_PWM_dutycycle(GPIO, 0) - e = pigpio.notify_pause(h) - CHECK(4, 2, e, 0, 0, "notify pause") + e = pi.notify_pause(h) + CHECK(4, 2, e, 0, 0, "notify pause") - e = pigpio.notify_close(h) - CHECK(4, 3, e, 0, 0, "notify close") + e = pi.notify_close(h) + CHECK(4, 3, e, 0, 0, "notify close") + + if f is not None: n = 0 s = 0 @@ -234,7 +251,6 @@ def t4(): if s != S: seq_ok = 0 - L = v & (1<<4) if n: @@ -249,19 +265,21 @@ def t4(): s += 1 n += 1 - # print(S, fl, t, hex(v)) - else: break f.close() CHECK(4, 4, seq_ok, 1, 0, "sequence numbers ok") - CHECK(4, 5, toggle_ok, 1, 0, "gpio toggled ok") - CHECK(4, 6, n, 80, 10, "number of notifications") + else: + + CHECK(4, 4, 0, 0, 0, "NOT APPLICABLE") + CHECK(4, 5, 0, 0, 0, "NOT APPLICABLE") + CHECK(4, 6, 0, 0, 0, "NOT APPLICABLE") + t5_count = 0 def t5cbf(gpio, level, tick): @@ -289,13 +307,13 @@ He capers nimbly in a lady's chamber To the lascivious pleasing of a lute. """ - print("Waveforms & serial read/write tests.") + print("Waveforms & bit bang serial read/write tests.") - t5cb = pigpio.callback(GPIO, pigpio.FALLING_EDGE, t5cbf) + t5cb = pi.callback(GPIO, pigpio.FALLING_EDGE, t5cbf) - pigpio.set_mode(GPIO, pigpio.OUTPUT) + pi.set_mode(GPIO, pigpio.OUTPUT) - e = pigpio.wave_clear() + e = pi.wave_clear() CHECK(5, 1, e, 0, 0, "callback, set mode, wave clear") wf = [] @@ -305,10 +323,10 @@ To the lascivious pleasing of a lute. wf.append(pigpio.pulse(1< 1: + tests = "" + for C in sys.argv[1]: + c = C.lower() + if c not in tests: + tests += c + +else: + tests = "0123456789" + +pi = pigpio.pi() + +if pi.connected: print("Connected to pigpio daemon.") - test = [t0, t1, t2, t3, t4, t5, t6, t7, t8, t9] + if '0' in tests: t0() + if '1' in tests: t1() + if '2' in tests: t2() + if '3' in tests: t3() + if '4' in tests: t4() + if '5' in tests: t5() + if '6' in tests: t6() + if '7' in tests: t7() + if '8' in tests: t8() + if '9' in tests: t9() + if 'a' in tests: ta() + if 'b' in tests: tb() + if 'c' in tests: tc() - for t in test: - t(); - - pigpio.stop() +pi.stop() diff --git a/x_pigpiod_if.c b/x_pigpiod_if.c index 787c6d4..b125e7d 100644 --- a/x_pigpiod_if.c +++ b/x_pigpiod_if.c @@ -16,6 +16,7 @@ sudo ./x_pigpiod_if #include #include #include +#include #include "pigpiod_if.h" @@ -349,7 +350,7 @@ To the lascivious pleasing of a lute.\n\ e = wave_tx_stop(); CHECK(5, 5, e, 0, 0, "wave tx stop"); - e = serial_read_open(GPIO, BAUD); + e = bb_serial_read_open(GPIO, BAUD); CHECK(5, 6, e, 0, 0, "serial read open"); wave_clear(); @@ -370,11 +371,11 @@ To the lascivious pleasing of a lute.\n\ c = t5_count - oc; CHECK(5, 10, c, 1702, 0, "wave tx busy, callback"); - c = serial_read(GPIO, text, sizeof(text)-1); + c = bb_serial_read(GPIO, text, sizeof(text)-1); if (c > 0) text[c] = 0; /* null terminate string */ CHECK(5, 11, strcmp(TEXT, text), 0, 0, "wave tx busy, serial read"); - e = serial_read_close(GPIO); + e = bb_serial_read_close(GPIO); CHECK(5, 12, e, 0, 0, "serial read close"); c = wave_get_micros(); @@ -603,10 +604,217 @@ void t9() CHECK(9, 4, e, 0, 0, "delete script"); } +void ta() +{ + int h, b, e; + char *TEXT; + char text[2048]; + + printf("Serial link tests.\n"); + + /* this test needs RXD and TXD to be connected */ + + h = serial_open("/dev/ttyAMA0", 57600, 0); + + CHECK(10, 1, h, 0, 0, "serial open"); + + time_sleep(0.1); /* allow time for transmission */ + + b = serial_read(h, text, sizeof(text)); /* flush buffer */ + + b = serial_data_available(h); + CHECK(10, 2, b, 0, 0, "serial data available"); + + TEXT = "\ +To be, or not to be, that is the question-\ +Whether 'tis Nobler in the mind to suffer\ +The Slings and Arrows of outrageous Fortune,\ +Or to take Arms against a Sea of troubles,\ +"; + e = serial_write(h, TEXT, strlen(TEXT)); + CHECK(10, 3, e, 0, 0, "serial write"); + + e = serial_write_byte(h, 0xAA); + e = serial_write_byte(h, 0x55); + e = serial_write_byte(h, 0x00); + e = serial_write_byte(h, 0xFF); + + CHECK(10, 4, e, 0, 0, "serial write byte"); + + time_sleep(0.1); /* allow time for transmission */ + + b = serial_data_available(h); + CHECK(10, 5, b, strlen(TEXT)+4, 0, "serial data available"); + + b = serial_read(h, text, strlen(TEXT)); + CHECK(10, 6, b, strlen(TEXT), 0, "serial read"); + if (b >= 0) text[b] = 0; + CHECK(10, 7, strcmp(TEXT, text), 0, 0, "serial read"); + + b = serial_read_byte(h); + CHECK(10, 8, b, 0xAA, 0, "serial read byte"); + + b = serial_read_byte(h); + CHECK(10, 9, b, 0x55, 0, "serial read byte"); + + b = serial_read_byte(h); + CHECK(10, 10, b, 0x00, 0, "serial read byte"); + + b = serial_read_byte(h); + CHECK(10, 11, b, 0xFF, 0, "serial read byte"); + + b = serial_data_available(h); + CHECK(10, 12, b, 0, 0, "serial data availabe"); + + e = serial_close(h); + CHECK(10, 13, e, 0, 0, "serial close"); +} + +void tb() +{ + int h, e, b, len; + char *exp; + char buf[128]; + + printf("SMBus / I2C tests."); + + /* this test requires an ADXL345 on I2C bus 1 addr 0x53 */ + + h = i2c_open(1, 0x53, 0); + CHECK(11, 1, h, 0, 0, "i2c open"); + + e = i2c_write_device(h, "\x00", 1); /* move to known register */ + CHECK(11, 2, e, 0, 0, "i2c write device"); + + b = i2c_read_device(h, buf, 1); + CHECK(11, 3, b, 1, 0, "i2c read device"); + CHECK(11, 4, buf[0], 0xE5, 0, "i2c read device"); + + b = i2c_read_byte(h); + CHECK(11, 5, b, 0xE5, 0, "i2c read byte"); + + b = i2c_read_byte_data(h, 0); + CHECK(11, 6, b, 0xE5, 0, "i2c read byte data"); + + b = i2c_read_byte_data(h, 48); + CHECK(11, 7, b, 2, 0, "i2c read byte data"); + + exp = "\x1D[aBcDeFgHjKM]"; + len = strlen(exp); + + e = i2c_write_device(h, exp, len); + CHECK(11, 8, e, 0, 0, "i2c write device"); + + e = i2c_write_device(h, "\x1D", 1); + b = i2c_read_device(h, buf, len-1); + CHECK(11, 9, b, len-1, 0, "i2c read device"); + CHECK(11, 10, strncmp(buf, exp+1, len-1), 0, 0, "i2c read device"); + + if (strncmp(buf, exp+1, len-1)) + printf("got [%.*s] expected [%.*s]\n", len-1, buf, len-1, exp+1); + + e = i2c_write_byte_data(h, 0x1d, 0xAA); + CHECK(11, 11, e, 0, 0, "i2c write byte data"); + + b = i2c_read_byte_data(h, 0x1d); + CHECK(11, 12, b, 0xAA, 0, "i2c read byte data"); + + e = i2c_write_byte_data(h, 0x1d, 0x55); + CHECK(11, 13, e, 0, 0, "i2c write byte data"); + + b = i2c_read_byte_data(h, 0x1d); + CHECK(11, 14, b, 0x55, 0, "i2c read byte data"); + + exp = "[1234567890#]"; + len = strlen(exp); + + e = i2c_write_block_data(h, 0x1C, exp, len); + CHECK(11, 15, e, 0, 0, "i2c write block data"); + + e = i2c_write_device(h, "\x1D", 1); + b = i2c_read_device(h, buf, len); + CHECK(11, 16, b, len, 0, "i2c read device"); + CHECK(11, 17, strncmp(buf, exp, len), 0, 0, "i2c read device"); + + if (strncmp(buf, exp, len)) + printf("got [%.*s] expected [%.*s]\n", len, buf, len, exp); + + b = i2c_read_i2c_block_data(h, 0x1D, buf, len); + CHECK(11, 18, b, len, 0, "i2c read i2c block data"); + CHECK(11, 19, strncmp(buf, exp, len), 0, 0, "i2c read i2c block data"); + + if (strncmp(buf, exp, len)) + printf("got [%.*s] expected [%.*s]\n", len, buf, len, exp); + + exp = "(-+=;:,<>!%)"; + len = strlen(exp); + + e = i2c_write_i2c_block_data(h, 0x1D, exp, len); + CHECK(11, 20, e, 0, 0, "i2c write i2c block data"); + + b = i2c_read_i2c_block_data(h, 0x1D, buf, len); + CHECK(11, 21, b, len, 0, "i2c read i2c block data"); + CHECK(11, 22, strncmp(buf, exp, len), 0, 0, "i2c read i2c block data"); + + if (strncmp(buf, exp, len)) + printf("got [%.*s] expected [%.*s]\n", len, buf, len, exp); + + e = i2c_close(h); + CHECK(11, 23, e, 0, 0, "i2c close"); +} + +void tc() +{ + int h, x, b, e; + char buf[128]; + + printf("SPI tests."); + + /* this test requires a MCP3202 on SPI channel 1 */ + + h = spi_open(1, 50000, 0); + CHECK(12, 1, h, 0, 0, "spi open"); + + + for (x=0; x<5; x++) + { + sprintf(buf, "\x01\x80"); + b = spi_xfer(h, buf, buf, 3); + CHECK(12, 2, b, 3, 0, "spi xfer"); + if (b == 3) + { + time_sleep(1.0); + printf("%d ", ((buf[1]&0x0F)*256)|buf[2]); + } + } + + e = spi_close(h); + CHECK(12, 99, e, 0, 0, "spi close"); +} + + int main(int argc, char *argv[]) { - int t, status; - void (*test[])(void) = {t0, t1, t2, t3, t4, t5, t6, t7, t8, t9}; + int i, t, c, status; + + char test[64]; + + if (argc > 1) + { + t = 0; + + for (i=0; i/dev/pigpio read -t 1 s /dev/pigpio read -t 1 s /dev/pigpio read -t 1 s /dev/pigpio read -t 1 s /dev/pigpio read -t 1 s /dev/pigpio +echo "wvas $GPIO 1200 0 0x6d 0x79 0x20 0x6e 0x61 0x6d 0x65 0x20 0x69 0x73 0x20 0x6a 0x6f 0x61 0x6e 0xc2 0xac" >/dev/pigpio read -t 1 s /dev/pigpio @@ -303,7 +303,7 @@ if [[ $s = 0 ]]; then echo "WRITE-d ok"; else echo "WRITE-d fail ($s)"; fi echo "wvclr" >/dev/pigpio read -t 1 s /dev/pigpio +echo "wvas $GPIO 300 0 0x74 0x68 0x69 0x73 0x20 0x69 0x73 0x20 0x74 0x68 0x65 0x20 0x77 0x69 0x6e 0x74 0x65 0x72 0x20 0x6f 0x66 0x20 0x6d 0x79 0x20 0x64 0x69 0x73 0x63 0x6f 0x6e 0x74 0x65 0x6e 0x74" >/dev/pigpio read -t 1 s /dev/pigpio