summaryrefslogtreecommitdiff
path: root/firmware
diff options
context:
space:
mode:
authoreaswaran2019-12-30 13:55:24 +0530
committereaswaran2019-12-30 13:55:24 +0530
commit8fca021e61fb72429fb8cf6c96fcd438ddbc3f68 (patch)
tree9d0ad890301c0c2a7d1dc2ecd4c20b1335dfa3d0 /firmware
parent3c3fbca7cba2509a558141d4a5532ce4fab723f8 (diff)
downloadopenplc_v2-8fca021e61fb72429fb8cf6c96fcd438ddbc3f68.tar.gz
openplc_v2-8fca021e61fb72429fb8cf6c96fcd438ddbc3f68.tar.bz2
openplc_v2-8fca021e61fb72429fb8cf6c96fcd438ddbc3f68.zip
[vishnu] unknown
Diffstat (limited to 'firmware')
-rwxr-xr-xfirmware/ADC.test.arduino/adc.ref2
-rwxr-xr-xfirmware/ADC.test.arduino/one/libraries/vishnuADC.cpp51
-rwxr-xr-xfirmware/ADC.test.arduino/one/libraries/vishnuADC.h121
-rwxr-xr-xfirmware/ADC.test.arduino/one/one.ino42
-rwxr-xr-x[-rw-r--r--]firmware/ADC.test.arduino/trial.c65
-rwxr-xr-xfirmware/ADC.test.arduino/trial2.c60
-rwxr-xr-xfirmware/bcm2835/asd1018.cpp73
-rwxr-xr-xfirmware/bcm2835/dinkan.cpp86
8 files changed, 500 insertions, 0 deletions
diff --git a/firmware/ADC.test.arduino/adc.ref b/firmware/ADC.test.arduino/adc.ref
new file mode 100755
index 0000000..8cb2251
--- /dev/null
+++ b/firmware/ADC.test.arduino/adc.ref
@@ -0,0 +1,2 @@
+One - https://forum.arduino.cc/index.php?topic=18827.0
+Two - https://forum.arduino.cc/index.php?topic=332030.0
diff --git a/firmware/ADC.test.arduino/one/libraries/vishnuADC.cpp b/firmware/ADC.test.arduino/one/libraries/vishnuADC.cpp
new file mode 100755
index 0000000..01d6931
--- /dev/null
+++ b/firmware/ADC.test.arduino/one/libraries/vishnuADC.cpp
@@ -0,0 +1,51 @@
+#include "vishnuADC.h"
+#include "Arduino.h"
+
+/**
+ * Constructor of the class
+ * @param io_pin_cs a byte indicating the pin to be use as the chip select pin (CS)
+ */
+ADS1118::ADS1118(uint8_t io_pin_cs) {
+ cs = io_pin_cs;
+}
+
+/**
+ * This method initialize the SPI port and the config register
+ */
+void ADS1118::begin() {
+ pinMode(cs, OUTPUT);
+ digitalWrite(cs, HIGH);
+ SPI.begin();
+ SPI.beginTransaction(SPISettings(SCLK, MSBFIRST, SPI_MODE1));
+ configRegister.bits={RESERVED, VALID_CFG, PULLUP, ADC_MODE, RATE_8SPS, SINGLE_SHOT, FSR_0256, DIFF_0_1, START_NOW}; //Default values
+}
+
+/**
+ * Getting the temperature in degrees celsius from the internal sensor of the ADS1118
+ * @return A double (32bits) containing the temperature in degrees celsius of the internal sensor
+ */
+double ADS1118::getTemperature() {
+ uint16_t convRegister;
+ uint8_t dataMSB, dataLSB, configMSB, configLSB, count=0;
+ if(lastSensorMode==TEMP_MODE)
+ count=1; //Lucky you! We don't have to read twice the sensor
+ else
+ configRegister.bits.sensorMode=TEMP_MODE; //Sorry but we will have to read twice the sensor
+ do{
+ digitalWrite(cs, LOW);
+ dataMSB = SPI.transfer(configRegister.byte.msb);
+ dataLSB = SPI.transfer(configRegister.byte.lsb);
+ configMSB = SPI.transfer(configRegister.byte.msb);
+ configLSB = SPI.transfer(configRegister.byte.lsb);
+ digitalWrite(cs, HIGH);
+ for(int i=0;i<CONV_TIME[configRegister.bits.rate];i++) //Lets wait the conversion time
+ delayMicroseconds(1000);
+ count++;
+ }while (count<=1); //We make two readings because the second reading is the temperature.
+ convRegister = ((dataMSB << 8) | (dataLSB))>>4;
+ if((convRegister<<2) >= 0x8000){
+ convRegister=((~convRegister)>>2)+1; //Converting to right-justified and applying binary twos complement format
+ return (double)(convRegister*0.03125*-1);
+ }
+ return (double)convRegister*0.03125;
+} \ No newline at end of file
diff --git a/firmware/ADC.test.arduino/one/libraries/vishnuADC.h b/firmware/ADC.test.arduino/one/libraries/vishnuADC.h
new file mode 100755
index 0000000..33b0fb5
--- /dev/null
+++ b/firmware/ADC.test.arduino/one/libraries/vishnuADC.h
@@ -0,0 +1,121 @@
+#ifndef vishnuADC
+#define vishnuADC
+
+#include "Arduino.h"
+#include <SPI.h>
+
+/**
+* Union representing the "config register" in 3 ways:
+* bits, word (16 bits) and nibbles (4 bits)
+* (See the datasheet [1] for more information)
+*/
+///Union configuration register
+union Config {
+ ///Structure of the config register of the ADS1118. (See datasheet [1])
+ struct {
+ uint8_t reserved:1; ///< "Reserved" bit
+ uint8_t noOperation:2; ///< "NOP" bits
+ uint8_t pullUp:1; ///< "PULL_UP_EN" bit
+ uint8_t sensorMode:1; ///< "TS_MODE" bit
+ uint8_t rate:3; ///< "DR" bits
+ uint8_t operatingMode:1;///< "MODE" bit
+ uint8_t pga:3; ///< "PGA" bits
+ uint8_t mux:3; ///< "MUX" bits
+ uint8_t singleStart:1; ///< "SS" bit
+ } bits;
+ uint16_t word; ///< Representation in word (16-bits) format
+ struct {
+ uint8_t lsb; ///< Byte LSB
+ uint8_t msb; ///< Byte MSB
+ } byte; ///< Representation in bytes (8-bits) format
+};
+
+/**
+ * Class representing the ADS1118 sensor chip
+ * @author Alvaro Salazar <alvaro@denkitronik.com>
+ */
+class ADS1118 {
+ public:
+ ADS1118(uint8_t io_pin_cs); ///< Constructor
+ void begin(); ///< This method initialize the SPI port and the config register
+ double getTemperature(); ///< Getting the temperature in degrees celsius from the internal sensor of the ADS1118
+ uint16_t getADCValue(uint8_t inputs);///< Getting a sample from the specified input
+ double getMilliVolts(uint8_t inputs);//< Getting the millivolts from the specified inputs
+ double getMilliVolts(); ///< Getting the millivolts from the settled inputs
+ void decodeConfigRegister(union Config configRegister); ///< Decoding a configRegister structure and then print it out to the Serial port
+ void setSamplingRate(uint8_t samplingRate);///< Setting the sampling rate specified in the config register
+ void setFullScaleRange(uint8_t fsr);///< Setting the full scale range in the config register
+ void setContinuousMode(); ///< Setting to continuous adquisition mode
+ void setSingleShotMode(); ///< Setting to single shot adquisition and power down mode
+ void disablePullup(); ///< Disabling the internal pull-up resistor of the DOUT pin
+ void enablePullup(); ///< Enabling the internal pull-up resistor of the DOUT pin
+ void setInputSelected(uint8_t input);///< Setting the inputs to be adquired in the config register.
+ //Input multiplexer configuration selection for bits "MUX"
+ //Differential inputs
+ const uint8_t DIFF_0_1 = 0b000; ///< Differential input: Vin=A0-A1
+ const uint8_t DIFF_0_3 = 0b001; ///< Differential input: Vin=A0-A3
+ const uint8_t DIFF_1_3 = 0b010; ///< Differential input: Vin=A1-A3
+ const uint8_t DIFF_2_3 = 0b011; ///< Differential input: Vin=A2-A3
+ //Single ended inputs
+ const uint8_t AIN_0 = 0b100; ///< Single ended input: Vin=A0
+ const uint8_t AIN_1 = 0b101; ///< Single ended input: Vin=A1
+ const uint8_t AIN_2 = 0b110; ///< Single ended input: Vin=A2
+ const uint8_t AIN_3 = 0b111; ///< Single ended input: Vin=A3
+
+ union Config configRegister; ///< Config register
+
+ //Bit constants
+ const long int SCLK = 1000000;///< ADS1118 SCLK frequency: 4000000 Hz Maximum for ADS1018 (4Mhz)
+
+ // Used by "SS" bit
+ const uint8_t START_NOW = 1; ///< Start of conversion in single-shot mode
+
+ // Used by "TS_MODE" bit
+ const uint8_t ADC_MODE = 0; ///< External (inputs) voltage reading mode
+ const uint8_t TEMP_MODE = 1; ///< Internal temperature sensor reading mode
+
+ // Used by "MODE" bit
+ const uint8_t CONTINUOUS = 0; ///< Continuous conversion mode
+ const uint8_t SINGLE_SHOT = 1; ///< Single-shot conversion and power down mode
+
+ // Used by "PULL_UP_EN" bit
+ const uint8_t PULLUP = 1; ///< Internal pull-up resistor enabled for DOUT ***DEFAULT
+ const uint8_t NO_PULLUP = 0; ///< Internal pull-up resistor disabled
+
+ // Used by "NOP" bits
+ const uint8_t VALID_CFG = 0b01; ///< Data will be written to Config register
+ const uint8_t NO_VALID_CFG= 0b00; ///< Data won't be written to Config register
+
+ // Used by "Reserved" bit
+ const uint8_t RESERVED = 1; ///< Its value is always 1, reserved
+
+ /*Full scale range (FSR) selection by "PGA" bits.
+ [Warning: this could increase the noise and the effective number of bits (ENOB). See tables above]*/
+ const uint8_t FSR_6144 = 0b000; ///< Range: ±6.144 v. LSB SIZE = 187.5μV
+ const uint8_t FSR_4096 = 0b001; ///< Range: ±4.096 v. LSB SIZE = 125μV
+ const uint8_t FSR_2048 = 0b010; ///< Range: ±2.048 v. LSB SIZE = 62.5μV ***DEFAULT
+ const uint8_t FSR_1024 = 0b011; ///< Range: ±1.024 v. LSB SIZE = 31.25μV
+ const uint8_t FSR_0512 = 0b100; ///< Range: ±0.512 v. LSB SIZE = 15.625μV
+ const uint8_t FSR_0256 = 0b111; ///< Range: ±0.256 v. LSB SIZE = 7.8125μV
+
+ /*Sampling rate selection by "DR" bits.
+ [Warning: this could increase the noise and the effective number of bits (ENOB). See tables above]*/
+ const uint8_t RATE_8SPS = 0b000; ///< 8 samples/s, Tconv=125ms
+ const uint8_t RATE_16SPS = 0b001; ///< 16 samples/s, Tconv=62.5ms
+ const uint8_t RATE_32SPS = 0b010; ///< 32 samples/s, Tconv=31.25ms
+ const uint8_t RATE_64SPS = 0b011; ///< 64 samples/s, Tconv=15.625ms
+ const uint8_t RATE_128SPS = 0b100; ///< 128 samples/s, Tconv=7.8125ms
+ const uint8_t RATE_250SPS = 0b101; ///< 250 samples/s, Tconv=4ms
+ const uint8_t RATE_475SPS = 0b110; ///< 475 samples/s, Tconv=2.105ms
+ const uint8_t RATE_860SPS = 0b111; ///< 860 samples/s, Tconv=1.163ms
+ // const uint8_t RATE_3300SPS = 0b110; ///< 860 samples/s, Tconv=1.163ms
+
+private:
+ uint8_t lastSensorMode=3; ///< Last sensor mode selected (ADC_MODE or TEMP_MODE or none)
+ uint8_t cs; ///< Chip select pin (choose one)
+ const float pgaFSR[8] = {6.144, 4.096, 2.048, 1.024, 0.512, 0.256, 0.256, 0.256};
+ const uint8_t CONV_TIME[8]={125, 63, 32, 16, 8, 4, 3, 2}; ///< Array containing the conversions time in ms
+
+};
+
+#endif
diff --git a/firmware/ADC.test.arduino/one/one.ino b/firmware/ADC.test.arduino/one/one.ino
new file mode 100755
index 0000000..862b0a7
--- /dev/null
+++ b/firmware/ADC.test.arduino/one/one.ino
@@ -0,0 +1,42 @@
+/**
+* Basic Example for Arduino Library for Texas Instruments ADS1118 - 16-Bit Analog-to-Digital Converter with
+* Internal Reference and Temperature Sensor
+*
+* @author Alvaro Salazar <alvaro@denkitronik.com>
+* http://www.denkitronik.com
+*
+*/
+
+#include "vishnuADC.h"
+#include <SPI.h>
+
+//Definition of the Arduino pin to be used as the chip select pin (SPI CS pin). Example: pin 5
+#define CS 5
+
+//Creating an ADS1118 object (object's name is ads1118)
+ADS1118 ads1118(CS);
+
+
+void setup(){
+ Serial.begin(115200);
+ ads1118.begin(); //Initialize the ADS1118. Default setting: PULLUP RESISTOR, ADC MODE, RATE 8SPS, SINGLE SHOT, ±0.256V, DIFFERENTIAL AIN0-AIN1
+
+ /* Changing the sampling rate. RATE_8SPS, RATE_16SPS, RATE_32SPS, RATE_64SPS, RATE_128SPS, RATE_250SPS, RATE_475SPS, RATE_860SPS*/
+ ads1118.setSamplingRate(ads1118.RATE_8SPS);
+
+ /* Changing the input selected. Differential inputs: DIFF_0_1, DIFF_0_3, DIFF_1_3, DIFF_2_3. Single ended input: AIN_0, AIN_1, AIN_2, AIN_3*/
+ ads1118.setInputSelected(ads1118.DIFF_0_1);
+
+ /* Changing the full scale range.
+ * FSR_6144 (±6.144V)*, FSR_4096(±4.096V)*, FSR_2048(±2.048V), FSR_1024(±1.024V), FSR_0512(±0.512V), FSR_0256(±0.256V).
+ * (*) No more than VDD + 0.3 V must be applied to this device.
+ */
+ ads1118.setFullScaleRange(ads1118.FSR_0256);
+}
+
+
+void loop(){
+ Serial.println(String(ads1118.getTemperature(),6)+" C"); //Getting temperature of the internal sensor
+ //Serial.println(String(ads1118.getMilliVolts(),10)+"mV"); //Getting millivolts measured in the input selected
+ delay(200); //You can use a delay to save power. The ADS1118 will be in power down state during all the delay time. (Optional)
+}
diff --git a/firmware/ADC.test.arduino/trial.c b/firmware/ADC.test.arduino/trial.c
index e69de29..fae88f6 100644..100755
--- a/firmware/ADC.test.arduino/trial.c
+++ b/firmware/ADC.test.arduino/trial.c
@@ -0,0 +1,65 @@
+
+#define SELPIN 10 //Selection Pin
+#define DATAOUT 11//MOSI
+#define DATAIN 12//MISO
+#define SPICLOCK 13//Clock
+int readvalue;
+
+void setup(){
+//set pin modes
+pinMode(SELPIN, OUTPUT);
+pinMode(DATAOUT, OUTPUT);
+pinMode(DATAIN, INPUT);
+pinMode(SPICLOCK, OUTPUT);
+//disable device to start with
+digitalWrite(SELPIN,HIGH);
+digitalWrite(DATAOUT,LOW);
+digitalWrite(SPICLOCK,LOW);
+
+Serial.begin(9600);
+}
+
+int read_adc(int channel){
+ int adcvalue = 0;
+ byte commandbits = B11000000; //command bits - start, mode, chn (3), dont care (3)
+
+ //allow channel selection
+ commandbits|=((channel-1)<<3);
+
+ digitalWrite(ADCSEL,LOW); //Select adc
+ // setup bits to be written
+ for (int i=7; i>=3; i--){
+ digitalWrite(DATAOUT,commandbits&1<<i);
+ //cycle clock
+ digitalWrite(SPICLOCK,HIGH);
+ digitalWrite(SPICLOCK,LOW);
+ }
+
+ digitalWrite(SPICLOCK,HIGH); //ignores 2 null bits
+ digitalWrite(SPICLOCK,LOW);
+ digitalWrite(SPICLOCK,HIGH);
+ digitalWrite(SPICLOCK,LOW);
+
+ //read bits from adc
+ for (int i=11; i>=0; i--){
+ adcvalue+=digitalRead(DATAIN)<<i;
+ //cycle clock
+ digitalWrite(SPICLOCK,HIGH);
+ digitalWrite(SPICLOCK,LOW);
+ }
+ digitalWrite(ADCSEL, HIGH); //turn off device
+ return adcvalue;
+}
+
+digitalWrite(SELPIN, HIGH); //turn off device
+return adcvalue;
+}
+
+void loop() {
+readvalue = read_adc(1);
+Serial.println(readvalue,DEC);
+readvalue = read_adc(2);
+Serial.println(readvalue,DEC);
+Serial.println(" ");
+delay(250);
+}
diff --git a/firmware/ADC.test.arduino/trial2.c b/firmware/ADC.test.arduino/trial2.c
new file mode 100755
index 0000000..e8cdfcf
--- /dev/null
+++ b/firmware/ADC.test.arduino/trial2.c
@@ -0,0 +1,60 @@
+/*
+
+SSTRB goes low when the ADC begins a conversion and goes
+high when the conversion is finished
+
+SSTRB goes low at the beginning of calibration and goes
+high to signal the end of calibration
+
+Control byte format
+7 - (MSB) START The first logic "1" bit, after CS goes low, defines the beginning of the Control Byte
+6 - UNI/BIP 1 = unipolar, 0 = bipolar
+5 - INT/EXT Selects the internal or external conversion clock. 1 = Internal, 0 = External.
+4 - M1 M1 M0 MODE
+3 - M0 0 0 24 External clocks per conversion (short acquisition mode)
+ 0 1 Start Calibration. Starts internal calibration.
+ 1 0 Software power-down mode
+ 1 1 32 External clocks per conversion (long acquisition mode)
+2 - programmable bit P2
+1 - programmable bit P1
+0 - programmable bit P0
+
+*/
+
+#define CALIBRATION 0b11101000
+#define START 0b11100000
+
+#include <SPI.h>
+int sstrb = 8;
+int adcPin = 9;
+int sdPin = 10;
+unsigned int adcValue = 0;
+byte LowByte,HighByte;
+
+void setup() {
+ pinMode(sstrb,INPUT);
+ pinMode(adcPin, OUTPUT);
+ pinMode(sdPin, OUTPUT);
+ digitalWrite(adcPin,HIGH);
+ digitalWrite(sdPin,HIGH);
+ Serial.begin(115200);
+ SPI.begin();
+ SPI.setBitOrder(MSBFIRST);
+ SPI.setClockDivider(SPI_CLOCK_DIV4);
+ SPI.setDataMode(SPI_MODE0);
+ delay(100);
+ digitalWrite(adcPin,LOW);
+ SPI.transfer(CALIBRATION); //kalibrálás
+ while(!digitalRead(sstrb)){}
+ SPI.transfer(START); //mérés indítás
+}
+
+
+void loop(){
+ while(!digitalRead(sstrb)){}
+ adcValue=SPI.transfer(START);
+ Serial.print("ADC: ");
+ Serial.println(adcValue);
+
+
+} \ No newline at end of file
diff --git a/firmware/bcm2835/asd1018.cpp b/firmware/bcm2835/asd1018.cpp
new file mode 100755
index 0000000..d5bff51
--- /dev/null
+++ b/firmware/bcm2835/asd1018.cpp
@@ -0,0 +1,73 @@
+//ADS1018 Configuration
+//http://www.ti.com/lit/ds/symlink/ads1018.pdf
+//Page 19-20
+
+// |(1=Start Single-shot), (0=no effect)
+// |
+// | |Mux (000 = P is AIN0 N is AIN1, 001 = P is AIN0 N is AIN3, 010 = P is AIN1 N is AIN3 , 011 = P is AIN2 N is AIN3
+// | | 100 = P is AIN0 N is GND, 101 = P is AIN1 N is GND, 110 = P is AIN2 N is GND, 111 = P is AIN3 N is GND)
+// | |
+// | | |PGA Gain (000 = ±6.144V, 001 = ±4.096V, 010 = ±2.048V, 011 = ±1.024V, 100 = ±0.512V, 101,110,111 = ±0.256V)
+// | | |
+// | | | |Mode (0 = Continuous conversion mode, 1 = Power-down and single-shot mode (default))
+// | | | |
+// | | | | |Data Rate (000 = 128SPS, 001 = 250SPS, 010 = 490SPS, 011 = 920SPS, 100 = 1600SPS, 101 = 2400SPS, 110 = 33005SPS, 111 = not used))
+// | | | | |
+// | | | | | |Sensor Mode (1=Internal Temp Mode, 0=ADC Mode)
+// | | | | | |
+// | | | | | | |PullUp (0 = Pullup resistor disabled on DOUT/DRDY pin, 1 = Pullup resistor enabled on DOUT/DRDY pin (default))
+// | | | | | | |
+// | | | | | | | |Update Config (01 = Valid data, update the Config register (default), 00,11,10 = do not update config register)
+// | | | | | | | |
+// | | | | | | | | |You must Always Write a 1 to this bit
+// | | | | | | | | |
+// 1 000 010 1 110 1 1 01 1 = 1000010111011011 = 0x85DB (this sets up a single shot for the internal temperature sensor 3300SPS)
+// 1 100 101 1 110 0 1 01 1 = 1100101111001011 = 0xCBCB (this sets up a single shot for single ended AIN0, PGA 0.256V, 860SPS)
+// 1 000 101 1 110 0 1 01 1 = 1000101111001011 = 0x8BCB (this sets up a single shot for differnetial AIN0 AIN1, PGA 0.256V, 860SPS)
+
+#include <bcm2835.h>
+#include <stdio.h>
+#include <unistd.h>
+
+int main(){
+ if (!bcm2835_init())
+ return 1;
+
+ bcm2835_spi_begin();
+ bcm2835_spi_setBitOrder(BCM2835_SPI_BIT_ORDER_MSBFIRST);
+ bcm2835_spi_setDataMode(BCM2835_SPI_MODE1);
+ bcm2835_spi_setClockDivider(BCM2835_SPI_CLOCK_DIVIDER_256);
+ bcm2835_spi_chipSelect(BCM2835_SPI_CS1);
+ bcm2835_spi_setChipSelectPolarity(BCM2835_SPI_CS0, LOW);
+
+ char txMSB[1], txLSB[1], rxMSB[1], rxLSB[1], configMSB[1], configLSB[1] ;
+
+ txMSB[0] = 0x85;
+ txLSB[0] = 0xDB;
+ rxMSB[0] = 0x00;
+ rxLSB[0] = 0x00;
+ configMSB[0] = 0x00;
+ configLSB[0] = 0x00;
+
+ printf("Intitial values \nmsb = %2.2X \nlsb = %2.2X\n", txMSB[0], txLSB[0]);
+
+ // int counter = 0;
+
+ // for (int i =0 ; i <100 ; i++){
+ while(1){
+ bcm2835_spi_transfernb(txMSB, rxMSB, 1);
+ usleep(350);
+ bcm2835_spi_transfernb(txLSB, rxLSB, 1);
+ usleep(350);
+ bcm2835_spi_transfernb(txMSB, configMSB, 1);
+ usleep(350);
+ bcm2835_spi_transfernb(txLSB, configLSB, 1);
+ printf("\nData \nmsb = %2.2X \nlsb = %2.2X \nconfig \nmsb = %2.2X \nlsb = %2.2X\n", rxMSB[0], rxLSB[0], configMSB[0], configLSB[0]);
+
+ }
+
+ printf("\nData \nmsb = %2.2X \nlsb = %2.2X \nconfig \nmsb = %2.2X \nlsb = %2.2X\n", rxMSB[0], rxLSB[0], configMSB[0], configLSB[0]);
+ bcm2835_spi_end();
+ bcm2835_close();
+ return 0;
+} \ No newline at end of file
diff --git a/firmware/bcm2835/dinkan.cpp b/firmware/bcm2835/dinkan.cpp
new file mode 100755
index 0000000..eff9774
--- /dev/null
+++ b/firmware/bcm2835/dinkan.cpp
@@ -0,0 +1,86 @@
+//ADS1018 Configuration
+//http://www.ti.com/lit/ds/symlink/ads1018.pdf
+//Page 19-20
+
+// |(1=Start Single-shot), (0=no effect)
+// |
+// | |Mux (000 = P is AIN0 N is AIN1, 001 = P is AIN0 N is AIN3, 010 = P is AIN1 N is AIN3 , 011 = P is AIN2 N is AIN3
+// | | 100 = P is AIN0 N is GND, 101 = P is AIN1 N is GND, 110 = P is AIN2 N is GND, 111 = P is AIN3 N is GND)
+// | |
+// | | |PGA Gain (000 = ±6.144V, 001 = ±4.096V, 010 = ±2.048V, 011 = ±1.024V, 100 = ±0.512V, 101,110,111 = ±0.256V)
+// | | |
+// | | | |Mode (0 = Continuous conversion mode, 1 = Power-down and single-shot mode (default))
+// | | | |
+// | | | | |Data Rate (000 = 128SPS, 001 = 250SPS, 010 = 490SPS, 011 = 920SPS, 100 = 1600SPS, 101 = 2400SPS, 110 = 33005SPS, 111 = not used))
+// | | | | |
+// | | | | | |Sensor Mode (1=Internal Temp Mode, 0=ADC Mode)
+// | | | | | |
+// | | | | | | |PullUp (0 = Pullup resistor disabled on DOUT/DRDY pin, 1 = Pullup resistor enabled on DOUT/DRDY pin (default))
+// | | | | | | |
+// | | | | | | | |Update Config (01 = Valid data, update the Config register (default), 00,11,10 = do not update config register)
+// | | | | | | | |
+// | | | | | | | | |You must Always Write a 1 to this bit
+// | | | | | | | | |
+// 1 000 010 1 110 1 1 01 1 = 1000010111011011 = 0x85DB (this sets up a single shot for the internal temperature sensor 3300SPS)
+// 1 100 101 1 110 0 1 01 1 = 1100101111001011 = 0xCBCB (this sets up a single shot for single ended AIN0, PGA 0.256V, 3300SPS)
+// 1 000 101 1 110 0 1 01 1 = 1000101111001011 = 0x8BCB (this sets up a single shot for differnetial AIN0 AIN1, PGA 0.256V, 3300SPS)
+
+#include <bcm2835.h>
+#include <stdio.h>
+#include <signal.h>
+#include <unistd.h>
+
+volatile sig_atomic_t flag = 0;
+
+void sigint(int a)
+{
+ flag = 1;
+}
+int main()
+{
+ if(!bcm2835_init())
+ return 1;
+
+ bcm2835_spi_begin();
+ bcm2835_spi_setBitOrder(BCM2835_SPI_BIT_ORDER_MSBFIRST);
+ bcm2835_spi_setDataMode(BCM2835_SPI_MODE1);
+ bcm2835_spi_setClockDivider(BCM2835_SPI_CLOCK_DIVIDER_256);
+ bcm2835_spi_chipSelect(BCM2835_SPI_CS1);
+ bcm2835_spi_setChipSelectPolarity(BCM2835_SPI_CS0, LOW);
+
+ uint8_t dataMSB = 0, dataLSB = 0, configMSB, configLSB ;
+ uint16_t convRegister;
+ double dinkan;
+
+ for(;;)
+ {
+ if (flag)
+ {
+ bcm2835_spi_end();
+ bcm2835_close();
+ break;
+ }
+
+ signal(SIGINT, sigint) ; // Ctr+C handling
+
+ dataMSB = bcm2835_spi_transfer(0x85);
+ dataLSB = bcm2835_spi_transfer(0xDB);
+ usleep(350);
+ configMSB = bcm2835_spi_transfer(0x85);
+ configLSB = bcm2835_spi_transfer(0xDB);
+
+ //Temp Calculation
+ convRegister = (((dataMSB)<<8 | (dataLSB)) >> 4); //Moving MSB and LSB to 12 bit and making it right-justified; 4 because 12bit value
+ convRegister &= 0x0FFF;
+ if((convRegister) >= 0x0800)
+ {
+ convRegister=((~convRegister)+1 & 0x0fff); //Applying binary twos complement format
+ dinkan = (double)(convRegister*0.125*-1);
+ }
+ dinkan = (double)(convRegister*0.125);
+
+ // printf("\nRecieved \nMSB = %2.2X \nLSB = %2.2X\n", dataMSB, dataLSB);
+ printf("Temp = %2.2f C\n\n", dinkan);
+ }
+ return 0;
+} \ No newline at end of file