Fixes warnings, bad code and code style
This commit is contained in:
parent
4cc1762851
commit
c836fbfbd9
|
@ -42,28 +42,25 @@
|
|||
#include "contiki.h"
|
||||
#include "dev/relay-phidget.h"
|
||||
|
||||
|
||||
#if 1
|
||||
#define PRINTF(...) printf(__VA_ARGS__)
|
||||
#else
|
||||
#define PRINTF(...)
|
||||
#endif
|
||||
|
||||
|
||||
#if 0
|
||||
#define PRINTFDEBUG(...) printf(__VA_ARGS__)
|
||||
#else
|
||||
#define PRINTFDEBUG(...)
|
||||
#endif
|
||||
|
||||
|
||||
#define RELAY_INTERVAL (CLOCK_SECOND)
|
||||
|
||||
PROCESS(test_process, "Relay test process");
|
||||
AUTOSTART_PROCESSES(&test_process);
|
||||
/*---------------------------------------------------------------------------*/
|
||||
static struct etimer et;
|
||||
static uint8_t status;
|
||||
static int8_t status;
|
||||
|
||||
PROCESS_THREAD(test_process, ev, data)
|
||||
{
|
||||
|
|
|
@ -38,7 +38,6 @@
|
|||
* Marcus Lundén, SICS <mlunden@sics.se>
|
||||
*/
|
||||
|
||||
|
||||
#include <stdio.h>
|
||||
#include "contiki.h"
|
||||
#include "i2cmaster.h"
|
||||
|
@ -50,9 +49,10 @@
|
|||
#define PRINTFDEBUG(...)
|
||||
#endif
|
||||
|
||||
#warning LIGHT SENSOR ZIGLET IS CURRENTLY BROKEN
|
||||
|
||||
/* Bitmasks and bit flag variable for keeping track of tmp102 status. */
|
||||
enum TSL2563_STATUSTYPES
|
||||
{
|
||||
enum TSL2563_STATUSTYPES {
|
||||
/* must be a bit and not more, not using 0x00. */
|
||||
INITED = 0x01,
|
||||
RUNNING = 0x02,
|
||||
|
@ -65,115 +65,114 @@ uint16_t
|
|||
calculateLux(uint16_t *buffer)
|
||||
{
|
||||
uint32_t ch0, ch1 = 0;
|
||||
uint32_t aux = (1<<14);
|
||||
uint32_t aux = (1 << 14);
|
||||
uint32_t ratio, lratio, tmp = 0;
|
||||
|
||||
ch0 = (buffer[0]*aux) >> 10;
|
||||
ch1 = (buffer[1]*aux) >> 10;
|
||||
ch0 = (buffer[0] * aux) >> 10;
|
||||
ch1 = (buffer[1] * aux) >> 10;
|
||||
|
||||
PRINTFDEBUG("B0 %u, B1 %u\n", buffer[0], buffer[1]);
|
||||
PRINTFDEBUG("ch0 %lu, ch1 %lu\n", ch0, ch1);
|
||||
|
||||
ratio = (ch1 << 10);
|
||||
ratio = ratio/ch0;
|
||||
lratio = (ratio+1) >> 1;
|
||||
ratio = ratio / ch0;
|
||||
lratio = (ratio + 1) >> 1;
|
||||
|
||||
PRINTFDEBUG("ratio %lu, lratio %lu\n", ratio, lratio);
|
||||
|
||||
if ((lratio >= 0) && (lratio <= K1T))
|
||||
tmp = (ch0*B1T) - (ch1*M1T);
|
||||
else if (lratio <= K2T)
|
||||
tmp = (ch0*B2T) - (ch1*M2T);
|
||||
else if (lratio <= K3T)
|
||||
tmp = (ch0*B3T) - (ch1*M3T);
|
||||
else if (lratio <= K4T)
|
||||
tmp = (ch0*B4T) - (ch1*M4T);
|
||||
else if (lratio <= K5T)
|
||||
tmp = (ch0*B5T) - (ch1*M5T);
|
||||
else if (lratio <= K6T)
|
||||
tmp = (ch0*B6T) - (ch1*M6T);
|
||||
else if (lratio <= K7T)
|
||||
tmp = (ch0*B7T) - (ch1*M7T);
|
||||
else if (lratio > K8T)
|
||||
tmp = (ch0*B8T) - (ch1*M8T);
|
||||
if((lratio >= 0) && (lratio <= K1T)) {
|
||||
tmp = (ch0 * B1T) - (ch1 * M1T);
|
||||
} else if(lratio <= K2T) {
|
||||
tmp = (ch0 * B2T) - (ch1 * M2T);
|
||||
} else if(lratio <= K3T) {
|
||||
tmp = (ch0 * B3T) - (ch1 * M3T);
|
||||
} else if(lratio <= K4T) {
|
||||
tmp = (ch0 * B4T) - (ch1 * M4T);
|
||||
} else if(lratio <= K5T) {
|
||||
tmp = (ch0 * B5T) - (ch1 * M5T);
|
||||
} else if(lratio <= K6T) {
|
||||
tmp = (ch0 * B6T) - (ch1 * M6T);
|
||||
} else if(lratio <= K7T) {
|
||||
tmp = (ch0 * B7T) - (ch1 * M7T);
|
||||
} else if(lratio > K8T) {
|
||||
tmp = (ch0 * B8T) - (ch1 * M8T);
|
||||
}
|
||||
|
||||
if (tmp < 0) tmp = 0;
|
||||
if(tmp < 0) {
|
||||
tmp = 0;
|
||||
}
|
||||
|
||||
tmp += (1<<13);
|
||||
tmp += (1 << 13);
|
||||
|
||||
PRINTFDEBUG("tmp %lu\n", tmp);
|
||||
|
||||
return (tmp >> 14);
|
||||
return tmp >> 14;
|
||||
}
|
||||
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/* Init the light ziglet sensor: ports, pins, registers, interrupts (none enabled), I2C,
|
||||
default threshold values etc. */
|
||||
|
||||
void
|
||||
light_ziglet_init (void)
|
||||
light_ziglet_init(void)
|
||||
{
|
||||
if (!(_TSL2563_STATUS & INITED))
|
||||
{
|
||||
PRINTFDEBUG ("light ziglet init\n");
|
||||
_TSL2563_STATUS |= INITED;
|
||||
if(!(_TSL2563_STATUS & INITED)) {
|
||||
PRINTFDEBUG("light ziglet init\n");
|
||||
_TSL2563_STATUS |= INITED;
|
||||
|
||||
/* Set up ports and pins for I2C communication */
|
||||
i2c_enable ();
|
||||
return;
|
||||
}
|
||||
/* Set up ports and pins for I2C communication */
|
||||
i2c_enable();
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/* Write to a 16-bit register.
|
||||
args:
|
||||
reg register to write to
|
||||
val value to write
|
||||
*/
|
||||
*/
|
||||
|
||||
void
|
||||
tsl2563_write_reg (uint8_t reg, uint16_t val)
|
||||
tsl2563_write_reg(uint8_t reg, uint16_t val)
|
||||
{
|
||||
uint8_t tx_buf[] = { reg, 0x00, 0x00 };
|
||||
|
||||
tx_buf[1] = (uint8_t) (val >> 8);
|
||||
tx_buf[2] = (uint8_t) (val & 0x00FF);
|
||||
tx_buf[1] = (uint8_t)(val >> 8);
|
||||
tx_buf[2] = (uint8_t)(val & 0x00FF);
|
||||
|
||||
i2c_transmitinit (TSL2563_ADDR);
|
||||
while (i2c_busy ());
|
||||
PRINTFDEBUG ("I2C Ready to TX\n");
|
||||
i2c_transmitinit(TSL2563_ADDR);
|
||||
while(i2c_busy());
|
||||
PRINTFDEBUG("I2C Ready to TX\n");
|
||||
|
||||
i2c_transmit_n (3, tx_buf);
|
||||
while (i2c_busy ());
|
||||
PRINTFDEBUG ("WRITE_REG 0x%04X @ reg 0x%02X\n", val, reg);
|
||||
i2c_transmit_n(3, tx_buf);
|
||||
while(i2c_busy());
|
||||
PRINTFDEBUG("WRITE_REG 0x%04X @ reg 0x%02X\n", val, reg);
|
||||
}
|
||||
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/* Read register.
|
||||
args:
|
||||
reg what register to read
|
||||
returns the value of the read register type uint16_t
|
||||
*/
|
||||
*/
|
||||
|
||||
uint16_t
|
||||
tsl2563_read_reg (uint8_t reg)
|
||||
tsl2563_read_reg(uint8_t reg)
|
||||
{
|
||||
uint16_t readBuf[] = {0x00, 0x00};
|
||||
uint8_t buf[] = { 0x00, 0x00, 0x00, 0x00};
|
||||
uint16_t readBuf[] = { 0x00, 0x00 };
|
||||
uint8_t buf[] = { 0x00, 0x00, 0x00, 0x00 };
|
||||
uint16_t retVal = 0;
|
||||
uint8_t rtx = reg;
|
||||
|
||||
// Transmit the register to read
|
||||
i2c_transmitinit (TSL2563_ADDR);
|
||||
while (i2c_busy ());
|
||||
i2c_transmit_n (1, &rtx);
|
||||
while (i2c_busy ());
|
||||
/* Transmit the register to read */
|
||||
i2c_transmitinit(TSL2563_ADDR);
|
||||
while(i2c_busy());
|
||||
i2c_transmit_n(1, &rtx);
|
||||
while(i2c_busy());
|
||||
|
||||
// Receive the data
|
||||
i2c_receiveinit (TSL2563_ADDR);
|
||||
while (i2c_busy ());
|
||||
i2c_receive_n (4, &buf[0]);
|
||||
while (i2c_busy ());
|
||||
/* Receive the data */
|
||||
i2c_receiveinit(TSL2563_ADDR);
|
||||
while(i2c_busy());
|
||||
i2c_receive_n(4, &buf[0]);
|
||||
while(i2c_busy());
|
||||
|
||||
PRINTFDEBUG("\nb0 %u, b1 %u, b2 %u, b3 %u\n", buf[0], buf[1], buf[2], buf[3]);
|
||||
|
||||
|
@ -182,45 +181,41 @@ tsl2563_read_reg (uint8_t reg)
|
|||
|
||||
/* XXX Quick hack, was receiving dups bytes */
|
||||
|
||||
if(readBuf[0] == readBuf[1]){
|
||||
if(readBuf[0] == readBuf[1]) {
|
||||
tsl2563_read_reg(TSL2563_READ);
|
||||
return;
|
||||
return 0x00;
|
||||
} else {
|
||||
retVal = calculateLux(&readBuf);
|
||||
retVal = calculateLux(readBuf);
|
||||
return retVal;
|
||||
}
|
||||
}
|
||||
|
||||
uint16_t
|
||||
light_ziglet_on(void)
|
||||
{
|
||||
uint16_t data;
|
||||
uint8_t regon[] = { 0x00, TSL2563_PWRN };
|
||||
// Turn on the sensor
|
||||
i2c_transmitinit (TSL2563_ADDR);
|
||||
while (i2c_busy ());
|
||||
i2c_transmit_n (2, ®on);
|
||||
while (i2c_busy ());
|
||||
data = (uint16_t) tsl2563_read_reg (TSL2563_READ);
|
||||
/* Turn on the sensor */
|
||||
i2c_transmitinit(TSL2563_ADDR);
|
||||
while(i2c_busy());
|
||||
i2c_transmit_n(2, regon);
|
||||
while(i2c_busy());
|
||||
data = (uint16_t)tsl2563_read_reg(TSL2563_READ);
|
||||
return data;
|
||||
}
|
||||
|
||||
void
|
||||
light_ziglet_off(void)
|
||||
{
|
||||
uint8_t regoff = 0x00;
|
||||
// Turn off the sensor
|
||||
i2c_transmitinit (TSL2563_ADDR);
|
||||
while (i2c_busy ());
|
||||
i2c_transmit_n (1, ®off);
|
||||
while (i2c_busy ());
|
||||
/* Turn off the sensor */
|
||||
i2c_transmitinit(TSL2563_ADDR);
|
||||
while(i2c_busy());
|
||||
i2c_transmit_n(1, ®off);
|
||||
while(i2c_busy());
|
||||
return;
|
||||
}
|
||||
|
||||
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/* Read light ziglet sensor
|
||||
*/
|
||||
*/
|
||||
|
||||
uint16_t
|
||||
light_ziglet_read(void)
|
||||
|
@ -230,4 +225,3 @@ light_ziglet_read(void)
|
|||
light_ziglet_off();
|
||||
return lux;
|
||||
}
|
||||
|
||||
|
|
|
@ -43,8 +43,7 @@
|
|||
|
||||
static uint8_t controlPin;
|
||||
|
||||
enum PHIDGET_RELAY_STATUSTYPES
|
||||
{
|
||||
enum PHIDGET_RELAY_STATUSTYPES {
|
||||
/* must be a bit and not more, not using 0x00. */
|
||||
INITED = 0x01,
|
||||
RUNNING = 0x02,
|
||||
|
@ -59,49 +58,48 @@ void
|
|||
relay_enable(uint8_t pin)
|
||||
{
|
||||
|
||||
if (!(_RELAY_STATUS & INITED)){
|
||||
if(!(_RELAY_STATUS & INITED)) {
|
||||
|
||||
_RELAY_STATUS |= INITED;
|
||||
|
||||
// Selects the pin to be configure as the control pin of the relay module
|
||||
/* Selects the pin to be configure as the control pin of the relay module */
|
||||
controlPin = (1 << pin);
|
||||
|
||||
// Configures the control pin
|
||||
/* Configures the control pin */
|
||||
P6SEL &= ~controlPin;
|
||||
P6DIR |= controlPin;
|
||||
}
|
||||
}
|
||||
|
||||
/*---------------------------------------------------------------------------*/
|
||||
|
||||
void
|
||||
relay_on()
|
||||
{
|
||||
if ((_RELAY_STATUS & INITED)){
|
||||
if((_RELAY_STATUS & INITED)) {
|
||||
P6OUT |= controlPin;
|
||||
}
|
||||
}
|
||||
|
||||
/*---------------------------------------------------------------------------*/
|
||||
void
|
||||
relay_off()
|
||||
{
|
||||
if ((_RELAY_STATUS & INITED)){
|
||||
if((_RELAY_STATUS & INITED)) {
|
||||
P6OUT &= ~controlPin;
|
||||
}
|
||||
}
|
||||
|
||||
/*---------------------------------------------------------------------------*/
|
||||
|
||||
uint8_t
|
||||
int8_t
|
||||
relay_toggle()
|
||||
{
|
||||
uint8_t status;
|
||||
if ((_RELAY_STATUS & INITED)){
|
||||
if((_RELAY_STATUS & INITED)) {
|
||||
P6OUT ^= controlPin;
|
||||
if((P6OUT & controlPin)) return 1;
|
||||
if((P6OUT & controlPin)) {
|
||||
return 1;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
return -1;
|
||||
}
|
||||
/*---------------------------------------------------------------------------*/
|
||||
|
||||
|
|
|
@ -44,7 +44,6 @@ void relay_enable(uint8_t pin);
|
|||
|
||||
void relay_on();
|
||||
void relay_off();
|
||||
uint8_t relay_toogle();
|
||||
|
||||
int8_t relay_toogle();
|
||||
|
||||
#endif /* RELAY_PHIDGET_H_ */
|
||||
|
|
|
@ -38,13 +38,11 @@
|
|||
* Jelmer Tiete, VUB <jelmer@tiete.be>
|
||||
*/
|
||||
|
||||
|
||||
#include <stdio.h>
|
||||
#include "contiki.h"
|
||||
#include "tlc59116.h"
|
||||
#include "i2cmaster.h"
|
||||
|
||||
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/* Write to a register.
|
||||
* args:
|
||||
|
@ -76,17 +74,16 @@ tlc59116_write_reg(uint8_t reg, uint8_t val)
|
|||
*/
|
||||
|
||||
void
|
||||
tlc59116_write_stream(uint8_t len, uint8_t * data)
|
||||
tlc59116_write_stream(uint8_t len, uint8_t *data)
|
||||
{
|
||||
i2c_transmitinit(TLC59116_ADDR);
|
||||
while(i2c_busy());
|
||||
PRINTFDEBUG("I2C Ready to TX(stream)\n");
|
||||
|
||||
i2c_transmit_n(len, data); // start tx and send conf reg
|
||||
i2c_transmit_n(len, data); /* start tx and send conf reg */
|
||||
while(i2c_busy());
|
||||
PRINTFDEBUG("WRITE_STR %u B to 0x%02X\n", len, data[0]);
|
||||
}
|
||||
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/* Read one register.
|
||||
* args:
|
||||
|
@ -116,7 +113,6 @@ tlc59116_read_reg(uint8_t reg)
|
|||
|
||||
return retVal;
|
||||
}
|
||||
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/* Read several registers in a stream.
|
||||
* args:
|
||||
|
@ -126,7 +122,7 @@ tlc59116_read_reg(uint8_t reg)
|
|||
*/
|
||||
|
||||
void
|
||||
tlc59116_read_stream(uint8_t reg, uint8_t len, uint8_t * whereto)
|
||||
tlc59116_read_stream(uint8_t reg, uint8_t len, uint8_t *whereto)
|
||||
{
|
||||
uint8_t rtx = reg;
|
||||
|
||||
|
@ -144,7 +140,6 @@ tlc59116_read_stream(uint8_t reg, uint8_t len, uint8_t * whereto)
|
|||
i2c_receive_n(len, whereto);
|
||||
while(i2c_busy());
|
||||
}
|
||||
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/* Set pwm value for individual led. Make sure PWM mode is enabled.
|
||||
* args:
|
||||
|
@ -155,13 +150,12 @@ tlc59116_read_stream(uint8_t reg, uint8_t len, uint8_t * whereto)
|
|||
void
|
||||
tlc59116_led(uint8_t led, uint8_t pwm)
|
||||
{
|
||||
if(led < 0 | led > 15) {
|
||||
if((led < 0) || (led > 15)) {
|
||||
PRINTFDEBUG("TLC59116: wrong led value.");
|
||||
} else {
|
||||
tlc59116_write_reg(led + TLC59116_PWM0, pwm);
|
||||
}
|
||||
}
|
||||
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/* Init the led driver: ports, pins, registers, interrupts (none enabled), I2C,
|
||||
* default threshold values etc.
|
||||
|
@ -180,8 +174,8 @@ tlc59116_init(void)
|
|||
/*Set all PWM values to 0x00 (off) */
|
||||
/*This would maybe be better with a SWRST */
|
||||
uint8_t tx_buf[] =
|
||||
{ TLC59116_PWM0_AUTOINCR, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 };
|
||||
tlc59116_write_stream(17, &tx_buf);
|
||||
{ TLC59116_PWM0_AUTOINCR, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 };
|
||||
tlc59116_write_stream(17, tx_buf);
|
||||
|
||||
/* set all leds to PWM control */
|
||||
tlc59116_write_reg(TLC59116_LEDOUT0, TLC59116_LEDOUT_PWM);
|
||||
|
|
|
@ -38,137 +38,125 @@
|
|||
* Marcus Lundén, SICS <mlunden@sics.se>
|
||||
*/
|
||||
|
||||
|
||||
#include <stdio.h>
|
||||
#include "contiki.h"
|
||||
#include "i2cmaster.h"
|
||||
#include "tmp102.h"
|
||||
|
||||
|
||||
|
||||
/* Bitmasks and bit flag variable for keeping track of tmp102 status. */
|
||||
enum TMP102_STATUSTYPES
|
||||
{
|
||||
enum TMP102_STATUSTYPES {
|
||||
/* must be a bit and not more, not using 0x00. */
|
||||
INITED = 0x01,
|
||||
RUNNING = 0x02,
|
||||
STOPPED = 0x04,
|
||||
LOW_POWER = 0x08,
|
||||
AAA = 0x10, // available to extend this...
|
||||
BBB = 0x20, // available to extend this...
|
||||
CCC = 0x40, // available to extend this...
|
||||
DDD = 0x80 // available to extend this...
|
||||
AAA = 0x10, /* available to extend this... */
|
||||
BBB = 0x20, /* available to extend this... */
|
||||
CCC = 0x40, /* available to extend this... */
|
||||
DDD = 0x80 /* available to extend this... */
|
||||
};
|
||||
static enum TMP102_STATUSTYPES _TMP102_STATUS = 0x00;
|
||||
|
||||
|
||||
/*---------------------------------------------------------------------------*/
|
||||
//PROCESS(tmp102_process, "Temperature Sensor process");
|
||||
/* PROCESS(tmp102_process, "Temperature Sensor process"); */
|
||||
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/* Init the temperature sensor: ports, pins, registers, interrupts (none enabled), I2C,
|
||||
default threshold values etc. */
|
||||
|
||||
void
|
||||
tmp102_init (void)
|
||||
tmp102_init(void)
|
||||
{
|
||||
if (!(_TMP102_STATUS & INITED))
|
||||
{
|
||||
PRINTFDEBUG ("TMP102 init\n");
|
||||
_TMP102_STATUS |= INITED;
|
||||
/* Power Up TMP102 via pin */
|
||||
TMP102_PWR_DIR |= TMP102_PWR_PIN;
|
||||
TMP102_PWR_SEL &= ~TMP102_PWR_SEL;
|
||||
TMP102_PWR_SEL2 &= ~TMP102_PWR_SEL;
|
||||
TMP102_PWR_REN &= ~TMP102_PWR_SEL;
|
||||
TMP102_PWR_OUT |= TMP102_PWR_PIN;
|
||||
if(!(_TMP102_STATUS & INITED)) {
|
||||
PRINTFDEBUG("TMP102 init\n");
|
||||
_TMP102_STATUS |= INITED;
|
||||
/* Power Up TMP102 via pin */
|
||||
TMP102_PWR_DIR |= TMP102_PWR_PIN;
|
||||
TMP102_PWR_SEL &= ~TMP102_PWR_SEL;
|
||||
TMP102_PWR_SEL2 &= ~TMP102_PWR_SEL;
|
||||
TMP102_PWR_REN &= ~TMP102_PWR_SEL;
|
||||
TMP102_PWR_OUT |= TMP102_PWR_PIN;
|
||||
|
||||
/* Set up ports and pins for I2C communication */
|
||||
i2c_enable ();
|
||||
|
||||
}
|
||||
/* Set up ports and pins for I2C communication */
|
||||
i2c_enable();
|
||||
}
|
||||
}
|
||||
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/* Write to a 16-bit register.
|
||||
args:
|
||||
reg register to write to
|
||||
val value to write
|
||||
*/
|
||||
*/
|
||||
|
||||
void
|
||||
tmp102_write_reg (uint8_t reg, uint16_t val)
|
||||
tmp102_write_reg(uint8_t reg, uint16_t val)
|
||||
{
|
||||
uint8_t tx_buf[] = { reg, 0x00, 0x00 };
|
||||
|
||||
tx_buf[1] = (uint8_t) (val >> 8);
|
||||
tx_buf[2] = (uint8_t) (val & 0x00FF);
|
||||
tx_buf[1] = (uint8_t)(val >> 8);
|
||||
tx_buf[2] = (uint8_t)(val & 0x00FF);
|
||||
|
||||
i2c_transmitinit (TMP102_ADDR);
|
||||
while (i2c_busy ());
|
||||
PRINTFDEBUG ("I2C Ready to TX\n");
|
||||
i2c_transmitinit(TMP102_ADDR);
|
||||
while(i2c_busy());
|
||||
PRINTFDEBUG("I2C Ready to TX\n");
|
||||
|
||||
i2c_transmit_n (3, tx_buf);
|
||||
while (i2c_busy ());
|
||||
PRINTFDEBUG ("WRITE_REG 0x%04X @ reg 0x%02X\n", val, reg);
|
||||
i2c_transmit_n(3, tx_buf);
|
||||
while(i2c_busy());
|
||||
PRINTFDEBUG("WRITE_REG 0x%04X @ reg 0x%02X\n", val, reg);
|
||||
}
|
||||
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/* Read register.
|
||||
args:
|
||||
reg what register to read
|
||||
returns the value of the read register type uint16_t
|
||||
*/
|
||||
*/
|
||||
|
||||
uint16_t
|
||||
tmp102_read_reg (uint8_t reg)
|
||||
tmp102_read_reg(uint8_t reg)
|
||||
{
|
||||
uint8_t buf[] = { 0x00, 0x00 };
|
||||
uint16_t retVal = 0;
|
||||
uint8_t rtx = reg;
|
||||
PRINTFDEBUG ("READ_REG 0x%02X\n", reg);
|
||||
PRINTFDEBUG("READ_REG 0x%02X\n", reg);
|
||||
|
||||
// transmit the register to read
|
||||
i2c_transmitinit (TMP102_ADDR);
|
||||
while (i2c_busy ());
|
||||
i2c_transmit_n (1, &rtx);
|
||||
while (i2c_busy ());
|
||||
/* transmit the register to read */
|
||||
i2c_transmitinit(TMP102_ADDR);
|
||||
while(i2c_busy());
|
||||
i2c_transmit_n(1, &rtx);
|
||||
while(i2c_busy());
|
||||
|
||||
// receive the data
|
||||
i2c_receiveinit (TMP102_ADDR);
|
||||
while (i2c_busy ());
|
||||
i2c_receive_n (2, &buf[0]);
|
||||
while (i2c_busy ());
|
||||
/* receive the data */
|
||||
i2c_receiveinit(TMP102_ADDR);
|
||||
while(i2c_busy());
|
||||
i2c_receive_n(2, &buf[0]);
|
||||
while(i2c_busy());
|
||||
|
||||
retVal = (uint16_t) (buf[0] << 8 | (buf[1]));
|
||||
retVal = (uint16_t)(buf[0] << 8 | (buf[1]));
|
||||
|
||||
return retVal;
|
||||
}
|
||||
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/* Read temperature in a raw format. Further processing will be needed
|
||||
to make an interpretation of these 12 or 13-bit data, depending on configuration
|
||||
*/
|
||||
*/
|
||||
|
||||
uint16_t
|
||||
tmp102_read_temp_raw (void)
|
||||
tmp102_read_temp_raw(void)
|
||||
{
|
||||
uint16_t rd = 0;
|
||||
|
||||
rd = tmp102_read_reg (TMP102_TEMP);
|
||||
rd = tmp102_read_reg(TMP102_TEMP);
|
||||
|
||||
return rd;
|
||||
}
|
||||
|
||||
int16_t
|
||||
tmp102_read_temp_x100(void)
|
||||
{
|
||||
int16_t raw = 0;
|
||||
int8_t rd = 0;
|
||||
int16_t sign = 1;
|
||||
int16_t abstemp, temp_int;
|
||||
|
||||
raw = (int16_t) tmp102_read_reg (TMP102_TEMP);
|
||||
raw = (int16_t)tmp102_read_reg(TMP102_TEMP);
|
||||
if(raw < 0) {
|
||||
abstemp = (raw ^ 0xFFFF) + 1;
|
||||
sign = -1;
|
||||
|
@ -185,18 +173,17 @@ tmp102_read_temp_x100(void)
|
|||
temp_frac = ((abstemp >>4) % 16) * 625;
|
||||
Data could be multiplied by 63 to have less bit-growth and 1/1000 precision
|
||||
Data could be multiplied by 64 (<< 6) to trade-off precision for speed
|
||||
*/
|
||||
*/
|
||||
|
||||
return temp_int;
|
||||
}
|
||||
|
||||
/*---------------------------------------------------------------------------*/
|
||||
/* Simple Read temperature. Return is an integer with temperature in 1deg. precision
|
||||
Return value is a signed 8 bit integer.
|
||||
*/
|
||||
*/
|
||||
|
||||
int8_t
|
||||
tmp102_read_temp_simple (void)
|
||||
tmp102_read_temp_simple(void)
|
||||
{
|
||||
return (int8_t) tmp102_read_temp_x100() / 100;
|
||||
return (int8_t)tmp102_read_temp_x100() / 100;
|
||||
}
|
||||
|
|
Loading…
Reference in a new issue