mirror of
https://github.com/eclipse/upm.git
synced 2025-03-15 04:57:30 +03:00
mcp9808: Initial commit for MCP9808 precision temperature sensor.
Add support for MCP9808 precision temp sensor. Implements all features except for TCrit and TUpper and TLower locking. Functionality includes alert, interrupt, resolution and hysteresis control. Signed-off-by: Marc Graham <marc@m2ag.com> Signed-off-by: Mihai Tudor Panu <mihai.tudor.panu@intel.com>
This commit is contained in:
parent
422592f993
commit
85b5c8a64e
BIN
docs/images/mcp9808.jpg
Normal file
BIN
docs/images/mcp9808.jpg
Normal file
Binary file not shown.
After Width: | Height: | Size: 319 KiB |
@ -153,6 +153,7 @@ add_executable (urm37-uart-example urm37-uart.cxx)
|
||||
add_executable (adxrs610-example adxrs610.cxx)
|
||||
add_executable (bma220-example bma220.cxx)
|
||||
add_executable (dfrph-example dfrph.cxx)
|
||||
add_executable (mcp9808-example mcp9808.cxx)
|
||||
|
||||
include_directories (${PROJECT_SOURCE_DIR}/src/hmc5883l)
|
||||
include_directories (${PROJECT_SOURCE_DIR}/src/grove)
|
||||
@ -270,6 +271,7 @@ include_directories (${PROJECT_SOURCE_DIR}/src/urm37)
|
||||
include_directories (${PROJECT_SOURCE_DIR}/src/adxrs610)
|
||||
include_directories (${PROJECT_SOURCE_DIR}/src/bma220)
|
||||
include_directories (${PROJECT_SOURCE_DIR}/src/dfrph)
|
||||
include_directories (${PROJECT_SOURCE_DIR}/src/mcp9808)
|
||||
|
||||
target_link_libraries (hmc5883l-example hmc5883l ${CMAKE_THREAD_LIBS_INIT})
|
||||
target_link_libraries (groveled-example grove ${CMAKE_THREAD_LIBS_INIT})
|
||||
@ -424,3 +426,4 @@ target_link_libraries (urm37-uart-example urm37 ${CMAKE_THREAD_LIBS_INIT})
|
||||
target_link_libraries (adxrs610-example adxrs610 ${CMAKE_THREAD_LIBS_INIT})
|
||||
target_link_libraries (bma220-example bma220 ${CMAKE_THREAD_LIBS_INIT})
|
||||
target_link_libraries (dfrph-example dfrph ${CMAKE_THREAD_LIBS_INIT})
|
||||
target_link_libraries (mcp9808-example mcp9808 ${CMAKE_THREAD_LIBS_INIT})
|
||||
|
171
examples/c++/mcp9808.cxx
Normal file
171
examples/c++/mcp9808.cxx
Normal file
@ -0,0 +1,171 @@
|
||||
|
||||
#include "mraa.hpp"
|
||||
|
||||
#include <iostream>
|
||||
#include <unistd.h>
|
||||
#include "mcp9808.h"
|
||||
|
||||
|
||||
|
||||
int main()
|
||||
{
|
||||
|
||||
using namespace std;
|
||||
|
||||
int command;
|
||||
upm::MCP9808 *temp = new upm::MCP9808(6);
|
||||
|
||||
|
||||
do
|
||||
{
|
||||
|
||||
cout << endl;
|
||||
cout << "1 - read temp \t" ;
|
||||
cout << "2 - sleep mode \t";
|
||||
cout << "3 - wake up" << endl;
|
||||
cout << "4 - set mode to " << (temp->isCelsius() == true ? "Fahrenheit" : "Celcius") << endl;
|
||||
cout << "5 - show status bits" << endl;
|
||||
cout << "6 - Set Tcrit \t" ;
|
||||
cout << "7 - Set Tupper \t" ;
|
||||
cout << "8 - Set Tlower " << endl;
|
||||
cout << "9 - Display monitor temps " << endl;
|
||||
cout << "10 - Enable alert default\t";
|
||||
cout << "11 - Enable alert interrupt" << endl;
|
||||
cout << "12 - Clear interrupt \t" ;
|
||||
cout << "13 - Clear alert mode" << endl;
|
||||
cout << "14 - Get Hysteresis\t";
|
||||
cout << "15 - Set Hysteresis" << endl;
|
||||
cout << "16 - Get Resolution\t";
|
||||
cout << "17 - Set Resolution" << endl;
|
||||
cout << "18 - Get Manufacturer ID"<< endl;
|
||||
cout << "19 - Get Device ID" << endl;
|
||||
cout << "-1 - exit" << endl;
|
||||
cout << "Enter a command: ";
|
||||
cin >> command;
|
||||
|
||||
|
||||
switch(command)
|
||||
{
|
||||
float t;
|
||||
case 1:
|
||||
std::cout << "Temp: " << temp->getTemp() << "° " << (temp->isCelsius()? "Celsius" : "Fahrenheit")<< std::endl;
|
||||
break;
|
||||
case 2:
|
||||
cout << "shutdown sensor (sleep mode)" << endl;
|
||||
temp->shutDown();
|
||||
break;
|
||||
case 3:
|
||||
cout << "wake up sensor" << endl;
|
||||
temp->shutDown(false);
|
||||
break;
|
||||
case 4:
|
||||
cout << "set mode to " << (temp->isCelsius() ? "Fahrenheit" : "Celcius") << endl;
|
||||
temp->setMode(!temp->isCelsius());
|
||||
break;
|
||||
case 5:
|
||||
cout << "Tcrit = " << temp->isTcrit();
|
||||
cout << " Tupper = " << temp->isTupper();
|
||||
cout << " Tlower = " << temp->isTlower();
|
||||
break;
|
||||
case 6:
|
||||
cout << "enter a value";
|
||||
cin >> t;
|
||||
temp->setMonitorReg(temp->CRIT_TEMP, t);
|
||||
break;
|
||||
case 7:
|
||||
cout << "enter a value";
|
||||
cin >> t;
|
||||
temp->setMonitorReg(temp->UPPER_TEMP, t);
|
||||
break;
|
||||
case 8:
|
||||
cout << "enter a value";
|
||||
cin >> t;
|
||||
temp->setMonitorReg(temp->LOWER_TEMP, t);
|
||||
break;
|
||||
case 9:
|
||||
cout << "tcrit = " << temp->getMonitorReg(temp->CRIT_TEMP) << endl;
|
||||
cout << "tupper = " << temp->getMonitorReg(temp->UPPER_TEMP) << endl;
|
||||
cout << "tlower = " << temp->getMonitorReg(temp->LOWER_TEMP) << endl;
|
||||
break;
|
||||
case 10:
|
||||
cout << "set alert mode default" ;
|
||||
temp->setAlertMode(temp->ALERTCTRL);
|
||||
break;
|
||||
case 11:
|
||||
cout << "set alert mode interrupt";
|
||||
temp->setAlertMode(temp->ALERTMODE | temp->ALERTCTRL );
|
||||
break;
|
||||
case 12:
|
||||
temp->clearInterrupt();
|
||||
break;
|
||||
case 13:
|
||||
cout << "Clear alerts" << endl;
|
||||
temp->clearAlertMode();
|
||||
break;
|
||||
case 14:
|
||||
cout << "Hysteresis: " << temp->getHysteresis() << endl;
|
||||
break;
|
||||
case 15:
|
||||
int u;
|
||||
cout << "enter 1 to 4";
|
||||
cin >> u ;
|
||||
switch(u)
|
||||
{
|
||||
case 1:
|
||||
temp->setHysteresis(temp->HYST_0);
|
||||
break;
|
||||
case 2:
|
||||
temp->setHysteresis(temp->HYST_1_5);
|
||||
break;
|
||||
case 3:
|
||||
temp->setHysteresis(temp->HYST_3_0);
|
||||
break;
|
||||
case 4:
|
||||
default:
|
||||
temp->setHysteresis(temp->HYST_6_0);
|
||||
break;
|
||||
}
|
||||
break;
|
||||
case 16:
|
||||
cout << "Resolution: " << temp->getResolution() << endl;
|
||||
break;
|
||||
case 17:
|
||||
int v;
|
||||
cout << "enter 1 to 4";
|
||||
cin >> v ;
|
||||
switch(v)
|
||||
{
|
||||
case 1:
|
||||
temp->setResolution(temp->RES_LOW);
|
||||
break;
|
||||
case 2:
|
||||
temp->setResolution(temp->RES_MEDIUM);
|
||||
break;
|
||||
case 3:
|
||||
temp->setResolution(temp->RES_HIGH);
|
||||
break;
|
||||
case 4:
|
||||
default:
|
||||
temp->setResolution(temp->RES_PRECISION);
|
||||
break;
|
||||
}
|
||||
break;
|
||||
case 18:
|
||||
cout << "Manufacturer ID: " << std::hex << temp->getManufacturer() << endl;
|
||||
break;
|
||||
case 19:
|
||||
cout << "Get device ID: " << std::hex << temp->getDevicedId() << endl;
|
||||
break;
|
||||
case -1:
|
||||
break;
|
||||
default:
|
||||
cout << endl << "That option is not available. Try again" << endl;
|
||||
break;
|
||||
}
|
||||
|
||||
}while (command != -1 );
|
||||
|
||||
|
||||
|
||||
return MRAA_SUCCESS;
|
||||
}
|
70
examples/javascript/mcp9808.js
Normal file
70
examples/javascript/mcp9808.js
Normal file
@ -0,0 +1,70 @@
|
||||
/*jslint node:true, vars:true, bitwise:true, unparam:true */
|
||||
/*jshint unused:true */
|
||||
// Leave the above lines for propper jshinting
|
||||
//Type Node.js Here :)
|
||||
/*
|
||||
* The MIT License
|
||||
*
|
||||
* Author: Marc Graham <marc@m2ag.net>
|
||||
* Copyright (c) 2015 Intel Corporation.
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining
|
||||
* a copy of this software and associated documentation files (the
|
||||
* "Software"), to deal in the Software without restriction, including
|
||||
* without limitation the rights to use, copy, modify, merge, publish,
|
||||
* distribute, sublicense, and/or sell copies of the Software, and to
|
||||
* permit persons to whom the Software is furnished to do so, subject to
|
||||
* the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be
|
||||
* included in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
|
||||
* EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
|
||||
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
|
||||
* NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE
|
||||
* LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION
|
||||
* OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION
|
||||
* WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
|
||||
var mcp = require('jsupm_mcp9808');
|
||||
|
||||
var temp = new mcp.MCP9808(6);
|
||||
|
||||
console.log(temp.getTemp());
|
||||
|
||||
//Sleep mode:
|
||||
temp.shutDown();
|
||||
//wake up
|
||||
temp.shutDown(false);
|
||||
//set mode to report fahrenheit
|
||||
temp.setMode(false);
|
||||
//check reporting mode
|
||||
console.log(temp.isCelsius()) //False = fahrenheit
|
||||
//set mode to celsius
|
||||
temp.setMode();
|
||||
//read temp
|
||||
temp.getTemp();
|
||||
//check Tcrit, Tupper or Tlower status bits
|
||||
temp.isTcrit(); // true if over boundry.
|
||||
temp.isTupper();
|
||||
temp.isTlower();
|
||||
//set the values of monitior registers
|
||||
temp.setMonitorReg(mcp.MCP9808.CRIT_TEMP, 23);
|
||||
temp.setMonitorReg(mcp.MCP9808.LOWER_TEMP, 20);
|
||||
temp.setMonitorReg(mcp.MCP9808.UPPER_TEMP, 22);
|
||||
//read MonitorReg
|
||||
console.log("Tcrit = " + temp.getMonitorReg(mcp.MCP9808.CRIT_TEMP));
|
||||
console.log("Tcrit = " + temp.getMonitorReg(mcp.MCP9808.LOWER_TEMP));
|
||||
console.log("Tcrit = " + temp.getMonitorReg(mcp.MCP9808.UPPER_TEMP));
|
||||
|
||||
|
||||
process.exit(0);
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
5
src/mcp9808/CMakeLists.txt
Normal file
5
src/mcp9808/CMakeLists.txt
Normal file
@ -0,0 +1,5 @@
|
||||
set (libname "mcp9808")
|
||||
set (libdescription "upm mcp9808 Precision I2c temperature sensor")
|
||||
set (module_src ${libname}.cxx)
|
||||
set (module_h ${libname}.h)
|
||||
upm_module_init()
|
8
src/mcp9808/javaupm_mcp9808.i
Normal file
8
src/mcp9808/javaupm_mcp9808.i
Normal file
@ -0,0 +1,8 @@
|
||||
%module javaupm_mcp9808
|
||||
%include "../upm.i"
|
||||
|
||||
%{
|
||||
#include "mcp9808.h"
|
||||
%}
|
||||
|
||||
%include "mcp9808.h"
|
8
src/mcp9808/jsupm_mcp9808.i
Normal file
8
src/mcp9808/jsupm_mcp9808.i
Normal file
@ -0,0 +1,8 @@
|
||||
%module jsupm_mcp9808
|
||||
%include "../upm.i"
|
||||
|
||||
%{
|
||||
#include "mcp9808.h"
|
||||
%}
|
||||
|
||||
%include "mcp9808.h"
|
191
src/mcp9808/mcp9808.cxx
Normal file
191
src/mcp9808/mcp9808.cxx
Normal file
@ -0,0 +1,191 @@
|
||||
/*
|
||||
* Author: Marc Graham <marc@m2ag.net>
|
||||
* Copyright (c) 2015 Intel Corporation.
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining
|
||||
* a copy of this software and associated documentation files (the
|
||||
* "Software"), to deal in the Software without restriction, including
|
||||
* without limitation the rights to use, copy, modify, merge, publish,
|
||||
* distribute, sublicense, and/or sell copies of the Software, and to
|
||||
* permit persons to whom the Software is furnished to do so, subject to
|
||||
* the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be
|
||||
* included in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
|
||||
* EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
|
||||
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
|
||||
* NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE
|
||||
* LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION
|
||||
* OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION
|
||||
* WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
|
||||
|
||||
|
||||
#include "mcp9808.h"
|
||||
#include <cmath>
|
||||
|
||||
|
||||
using namespace upm;
|
||||
|
||||
MCP9808::MCP9808 (int bus, uint8_t address){
|
||||
m_name = "mcp9808";
|
||||
m_celsius = true;
|
||||
m_tcrit = false;
|
||||
m_tupper = false;
|
||||
m_tlower = false;
|
||||
if(!(i2c = new mraa::I2c(bus))){
|
||||
throw std::invalid_argument(std::string(__FUNCTION__) +": I2c.init() failed");
|
||||
return;
|
||||
}
|
||||
|
||||
if((i2c->address(address) != mraa::SUCCESS)){
|
||||
throw std::invalid_argument(std::string(__FUNCTION__) + ": I2c.address() failed");
|
||||
return;
|
||||
}
|
||||
|
||||
if(i2c->frequency( mraa::I2C_FAST) != mraa::SUCCESS){
|
||||
throw std::invalid_argument(std::string(__FUNCTION__) + ": I2c.frequency(I2C_STD) failed");
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
float
|
||||
MCP9808::getTemp(){
|
||||
uint16_t result;
|
||||
//Read the register
|
||||
result = i2c->readWordReg(MCP9808_REG_AMBIENT_TEMP);
|
||||
//Swap the bytes
|
||||
result = swapWord(result);
|
||||
//Get the flag bits.
|
||||
m_tcrit = (result & 0x8000) ;
|
||||
m_tupper = (result & 0x4000) ;
|
||||
m_tlower = (result & 0x2000) ;
|
||||
return getTempValue(result);
|
||||
}
|
||||
|
||||
void
|
||||
MCP9808::shutDown(bool sleep){
|
||||
if(sleep) this->updateConfigRegister(MCP9808_CONFIG_SHUTDOWN);
|
||||
else this->updateConfigRegister(~(MCP9808_CONFIG_SHUTDOWN), false);
|
||||
}
|
||||
|
||||
|
||||
void
|
||||
MCP9808::setMonitorReg(MCP9808_REG reg, float value){
|
||||
uint16_t t;
|
||||
if(m_celsius) t = value * 16.0;
|
||||
else t = ((value - 32) * 5.0/9.0) * 16.0 ;
|
||||
|
||||
t = swapWord(t);
|
||||
|
||||
if(i2c->writeWordReg(reg, t) != mraa::SUCCESS){
|
||||
throw std::invalid_argument(std::string(__FUNCTION__) + ": I2c.write() failed");
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
float
|
||||
MCP9808::getMonitorReg(MCP9808_REG reg){
|
||||
uint16_t value = i2c->readWordReg(reg);
|
||||
value = swapWord(value);
|
||||
return getTempValue(value);
|
||||
}
|
||||
|
||||
|
||||
void
|
||||
MCP9808::clearInterrupt(){
|
||||
this->updateConfigRegister(MCP9808_CONFIG_INTCLR);
|
||||
}
|
||||
|
||||
void
|
||||
MCP9808::setAlertMode(uint16_t command){
|
||||
this->updateConfigRegister(command);
|
||||
}
|
||||
|
||||
void
|
||||
MCP9808::clearAlertMode(){
|
||||
//Preserve hysteresis and shutdown settings but
|
||||
//set all alert settings to power on default.
|
||||
this->updateConfigRegister(0x2007, false);
|
||||
}
|
||||
|
||||
|
||||
void
|
||||
MCP9808::setHysteresis(MCP9808_CONFIG value){
|
||||
//Clear hysteresis first.
|
||||
this->updateConfigRegister(0xFFF9, false);
|
||||
this->updateConfigRegister(value);
|
||||
}
|
||||
|
||||
float
|
||||
MCP9808::getHysteresis(){
|
||||
uint16_t value = i2c->readWordReg(MCP9808_REG_CONFIG);
|
||||
value = (value >> 1 ) & 0xF ;
|
||||
float res = (value == 0) ? 0.0 : ( 1.5 * pow( 2.0 , value - 1 )) ;
|
||||
return (m_celsius) ? res : res * 9/5;
|
||||
}
|
||||
|
||||
|
||||
void
|
||||
MCP9808::setResolution(MCP9808_RESOLUTION value){
|
||||
if(i2c->writeReg(MCP9808_REG_RESOLUTION, value) != mraa::SUCCESS){
|
||||
throw std::invalid_argument(std::string(__FUNCTION__) + ": I2c.write() failed");
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
float
|
||||
MCP9808::getResolution(){
|
||||
uint8_t value = i2c->readReg(MCP9808_REG_RESOLUTION);
|
||||
return 0.5 * (1.0 / std::pow( 2.0, value));
|
||||
}
|
||||
|
||||
|
||||
uint16_t
|
||||
MCP9808::getManufacturer(){
|
||||
return swapWord(i2c->readWordReg(MCP9808_REG_MANUF_ID));
|
||||
}
|
||||
|
||||
uint16_t
|
||||
MCP9808::getDevicedId(){
|
||||
return swapWord(i2c->readWordReg(MCP9808_REG_DEVICE_ID));
|
||||
}
|
||||
|
||||
MCP9808::~MCP9808 (){
|
||||
delete i2c;
|
||||
}
|
||||
|
||||
|
||||
//Private functions
|
||||
|
||||
float
|
||||
MCP9808::getTempValue(uint16_t result){
|
||||
bool neg = (result & 0x1000);
|
||||
float res = (result & 0xFFF) / 16.0;
|
||||
if(neg) res = 0 - ( 256 - res );
|
||||
if(!m_celsius) res = res * 9.0/5.0 + 32;
|
||||
return res;
|
||||
}
|
||||
|
||||
void
|
||||
MCP9808::updateConfigRegister(uint16_t update, bool on){
|
||||
uint16_t reg = i2c->readWordReg(MCP9808_REG_CONFIG);
|
||||
if(on) reg |= update;
|
||||
else reg &= update;
|
||||
|
||||
if(i2c->writeWordReg(MCP9808_REG_CONFIG, reg) != mraa::SUCCESS){
|
||||
throw std::invalid_argument(std::string(__FUNCTION__) + ": I2c.write() failed");
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
uint16_t
|
||||
MCP9808::swapWord(uint16_t value){
|
||||
uint16_t res = value;
|
||||
return ((res & 0xFF) << 8) | ((res >> 8 ) & 0xFF);
|
||||
}
|
329
src/mcp9808/mcp9808.h
Normal file
329
src/mcp9808/mcp9808.h
Normal file
@ -0,0 +1,329 @@
|
||||
/*
|
||||
* Author: Marc Graham <marc@m2ag.net>
|
||||
* Copyright (c) 2015 Intel Corporation.
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining
|
||||
* a copy of this software and associated documentation files (the
|
||||
* "Software"), to deal in the Software without restriction, including
|
||||
* without limitation the rights to use, copy, modify, merge, publish,
|
||||
* distribute, sublicense, and/or sell copies of the Software, and to
|
||||
* permit persons to whom the Software is furnished to do so, subject to
|
||||
* the following conditions:
|
||||
*
|
||||
* The above copyright notice and this permission notice shall be
|
||||
* included in all copies or substantial portions of the Software.
|
||||
*
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
|
||||
* EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
|
||||
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
|
||||
* NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE
|
||||
* LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION
|
||||
* OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION
|
||||
* WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
|
||||
*/
|
||||
|
||||
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <iostream>
|
||||
#include <string>
|
||||
#include "mraa.hpp"
|
||||
#include "mraa/i2c.hpp"
|
||||
|
||||
#define MCP9808_REG_CONFIG 0x01
|
||||
#define MCP9808_REG_AMBIENT_TEMP 0x05
|
||||
#define MCP9808_REG_MANUF_ID 0x06
|
||||
#define MCP9808_REG_DEVICE_ID 0x07
|
||||
#define MCP9808_REG_RESOLUTION 0x08
|
||||
#define MCP9808_CONFIG_SHUTDOWN 0x0001
|
||||
#define MCP9808_CONFIG_CRITLOCKED 0x8000
|
||||
#define MCP9808_CONFIG_WINLOCKED 0x4000
|
||||
#define MCP9808_CONFIG_INTCLR 0x2000
|
||||
|
||||
namespace upm {
|
||||
/**
|
||||
* @library mcp9808
|
||||
* @sensor MCP9808
|
||||
* @comname MCP9808
|
||||
* @type Temperature, precision.
|
||||
* @man https://learn.adafruit.com/adafruit-mcp9808-precision-i2c-temperature-sensor-guide/overview
|
||||
* @man http://ww1.microchip.com/downloads/en/DeviceDoc/25095A.pdf
|
||||
* @con i2c
|
||||
*
|
||||
* @brief API for MCP9808 precision temprature sensor
|
||||
* The MCP9808 digital temperature sensor converts temperatures between -20°C and +100°C
|
||||
* to a digital word with ±0.5°C (max.) accuracy. The MCP9808 comes with user-programmable
|
||||
* registers that provide flexibility for temperature sensing applications. The registers
|
||||
* allow user-selectable settings such as Shutdown or low-power modes and the specification
|
||||
* of temperature Event and Critical output boundaries. When the temperature changes beyond
|
||||
* the specified boundary limits, the MCP9808 outputs an Event signal. The user has the
|
||||
* option of setting the event output signal polarity as an active-low or active-high
|
||||
* comparator output for thermostat operation, or as temperature event interrupt output
|
||||
* for microprocessor-based systems. The event output can also be configured as a Critical
|
||||
* temperature output.
|
||||
*
|
||||
* Tested with Adafriut MCP9808 board.
|
||||
*
|
||||
* @image html mcp9808.jpg
|
||||
* @snippet mcp9808.cxx Interesting
|
||||
*/
|
||||
class MCP9808 {
|
||||
|
||||
public:
|
||||
/**
|
||||
* @enum MCP9808_REG
|
||||
* @brief uint8_t enum containing register addresses
|
||||
* used for setting temp thresholds for MCP9808
|
||||
*
|
||||
* @var MCP9808_REG::UPPER_TEMP = 0x02
|
||||
* @var MCP9808_REG::LOWER_TEMP = 0x03
|
||||
* @var MCP9808_REG::CRIT_TEMP = 0x04
|
||||
*/
|
||||
typedef enum
|
||||
{
|
||||
UPPER_TEMP = 0x02,
|
||||
LOWER_TEMP = 0x03,
|
||||
CRIT_TEMP = 0x04,
|
||||
} MCP9808_REG;
|
||||
|
||||
/**
|
||||
* @enum MCP9808_RESOLUTION
|
||||
* @brief uint8_t enum containing the four possible
|
||||
* values for MCP9808 resolution register.
|
||||
*
|
||||
* @var MCP9808_RESOLUTION::RES_LOW = 0.5C
|
||||
* @var MCP9808_RESOLUTION::RES_MEDIUM = 0.25C
|
||||
* @var MCP9808_RESOLUTION::RES_HIGH = 0.125C
|
||||
* @var MCP9808_RESOLUTION::RES_PRECISION = (default) 0.0625C
|
||||
*/
|
||||
typedef enum
|
||||
{
|
||||
RES_LOW = 0x00,
|
||||
RES_MEDIUM = 0x01,
|
||||
RES_HIGH = 0x02,
|
||||
RES_PRECISION = 0x03
|
||||
} MCP9808_RESOLUTION;
|
||||
|
||||
/**
|
||||
* @enum MCP9808_CONFIG
|
||||
* @brief uint16_t enum containing alert and hysteresis options
|
||||
* for config register.
|
||||
*
|
||||
* @var MCP9808_CONFIG::ALERTSTAT - Alert Output Status bit
|
||||
* 0 = Alert output is not asserted by the device (power-up default)
|
||||
* 1 = Alert output is asserted as a comparator/Interrupt or critical
|
||||
* temperature output
|
||||
* @var MCP9808_CONFIG::ALERTCTRL - Alert Output Control bit
|
||||
* 0 = Disabled (power-up default)
|
||||
* 1 = Enabled
|
||||
* @var MCP9808_CONFIG::ALERTSEL - Alert Output Select bit
|
||||
* 0 = Alert output for TUPPER, TLOWER and TCRIT (power-up default)
|
||||
* 1 = TA > TCRIT only (TUPPER and TLOWER temperature boundaries are disabled)
|
||||
* @var MCP9808_CONFIG::ALERTPOL - Alert Output Polarity bit
|
||||
* 0 = Active-low (power-up default; pull-up resistor required)
|
||||
* 1 = Active-high
|
||||
* @var MCP9808_CONFIG::ALERTMODE - Alert Output Mode bit
|
||||
* 0 = Comparator output (power-up default)
|
||||
* 1 = Interrupt output
|
||||
* @var MCP9808_CONFIG::HYST_0 : 0°C
|
||||
* @var MCP9808_CONFIG::HYST_1_5 : +1.5°C
|
||||
* @var MCP9808_CONFIG::HYST_3_0 : +3.0°C
|
||||
* @var MCP9808_CONFIG::HYST_6_0 : +6.0°C
|
||||
*/
|
||||
typedef enum
|
||||
{
|
||||
ALERTSTAT = 0x1000,
|
||||
ALERTCTRL = 0x0800,
|
||||
ALERTSEL = 0x0400,
|
||||
ALERTPOL = 0x0200,
|
||||
ALERTMODE = 0x0100,
|
||||
HYST_0 = 0x0000,
|
||||
HYST_1_5 = 0x0002,
|
||||
HYST_3_0 = 0x0004,
|
||||
HYST_6_0 = 0x0006
|
||||
} MCP9808_CONFIG;
|
||||
|
||||
/**
|
||||
* MCP9808 constructor
|
||||
*
|
||||
* @param bus i2c bus the sensor is attached to.
|
||||
* @param address. Device address. Default is 0x18.
|
||||
*/
|
||||
MCP9808 (int bus, uint8_t address = 0x18);
|
||||
|
||||
/**
|
||||
* MCP9808 destructor
|
||||
*/
|
||||
~MCP9808 ();
|
||||
|
||||
/**
|
||||
* Returns the name of the sensor
|
||||
*/
|
||||
std::string name()
|
||||
{
|
||||
return m_name;
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns current temperature.
|
||||
*/
|
||||
float getTemp(void);
|
||||
|
||||
|
||||
/**
|
||||
* Will cause the devices to either sleep or wakeup.
|
||||
*
|
||||
* @param sleep . Bool, default true to sleep. false to wake.
|
||||
*/
|
||||
void shutDown(bool sleep = true);
|
||||
|
||||
/**
|
||||
* setMode - sets temperature reporting mode.
|
||||
*
|
||||
* @param celsius. Default is true. If false all
|
||||
* temps will be reported in fahrenhiet.
|
||||
*/
|
||||
void setMode(bool celsius = true)
|
||||
{
|
||||
m_celsius = celsius;
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns true if mode is celsius
|
||||
* False if fahrenheit.
|
||||
*/
|
||||
bool isCelsius(void)
|
||||
{
|
||||
return m_celsius;
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns true if TCrit threshold has been crossed
|
||||
* Reflects the state of the bit based on the most recent
|
||||
* readTemp() operation.
|
||||
*/
|
||||
bool isTcrit()
|
||||
{
|
||||
return m_tcrit;
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns true if TUpper threshold crossed
|
||||
* Reflects the state of the bit based on the most recent
|
||||
* readTemp() operation.
|
||||
*/
|
||||
bool isTupper()
|
||||
{
|
||||
return m_tupper;
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns true if TLower threshold crossed.
|
||||
* Reflects the state of the bit based on the most recent
|
||||
* readTemp() operation.
|
||||
*/
|
||||
bool isTlower()
|
||||
{
|
||||
return m_tlower;
|
||||
}
|
||||
|
||||
/**
|
||||
* Sets the value of TCrit, TUpper,TLower registers.
|
||||
*
|
||||
* @praam reg - MCP9808_REG enum UPPER_TEMP, LOWER_TEMP
|
||||
* or CRIT_TEMP.
|
||||
* @param value - float value representing the set value
|
||||
*/
|
||||
void setMonitorReg(MCP9808_REG reg, float value);
|
||||
|
||||
/**
|
||||
* Returns the current value of TCrit, TUpper, TLower
|
||||
* registers.
|
||||
*
|
||||
* @param reg - MCP9808_REG enum UPPER_TEMP, LOWER_TEMP
|
||||
* or CRIT_TEMP.
|
||||
*/
|
||||
float getMonitorReg(MCP9808_REG reg);
|
||||
|
||||
/**
|
||||
* Clears the interrupt when ALERT_MODE is set to
|
||||
* interrupt output and temp threshold crossed.
|
||||
*/
|
||||
void clearInterrupt(void);
|
||||
|
||||
/**
|
||||
* Sets alert mode. Can use values from MCP9808_CONFIG
|
||||
* enum. Values can be combined.
|
||||
*
|
||||
* @param command - a combination of options to set desired
|
||||
* alert mode. See spcec sheet.
|
||||
*/
|
||||
void setAlertMode(uint16_t command);
|
||||
|
||||
/**
|
||||
* Clears Alert Mode -- sets all params to default.
|
||||
*/
|
||||
void clearAlertMode(void);
|
||||
|
||||
/**
|
||||
* Sets hysteresis value.
|
||||
*
|
||||
* @param MCP9808_CONFIG enum value HYST_0, HYST_1_5,
|
||||
* HYST_3_0 or HYST_6_0
|
||||
*/
|
||||
void setHysteresis(MCP9808_CONFIG value);
|
||||
|
||||
/**
|
||||
* Returns hysteresis setting as a float value.
|
||||
*/
|
||||
float getHysteresis();
|
||||
|
||||
/**
|
||||
* Sets resolution of temperature conversion.
|
||||
*
|
||||
* @param value - MCP9808_RESOLUTION enum value.
|
||||
* RES_LOW = +0.5 C
|
||||
* RES_MEDIUM = +0.25 C
|
||||
* RES_HIGH = +0.125 C
|
||||
* RES_PRECISION = +0.0625 C (default).
|
||||
*/
|
||||
void setResolution(MCP9808_RESOLUTION value);
|
||||
|
||||
/**
|
||||
* Returns float value representing the current
|
||||
* resolution setting.
|
||||
*/
|
||||
float getResolution();
|
||||
|
||||
/**
|
||||
* Returns Manufacturer ID. Typically 0x0054;
|
||||
*/
|
||||
uint16_t getManufacturer();
|
||||
|
||||
/**
|
||||
* Returns device ID and revision. Typically 0x0400
|
||||
* With ID in the High byte.
|
||||
*/
|
||||
uint16_t getDevicedId();
|
||||
|
||||
|
||||
|
||||
|
||||
private:
|
||||
std::string m_name;
|
||||
bool m_celsius;
|
||||
bool m_tcrit;
|
||||
bool m_tupper;
|
||||
bool m_tlower;
|
||||
|
||||
mraa::I2c* i2c;
|
||||
|
||||
float getTempValue(uint16_t value);
|
||||
void updateConfigRegister(uint16_t update, bool on = true);
|
||||
uint16_t swapWord(uint16_t value);
|
||||
|
||||
|
||||
|
||||
};
|
||||
}
|
9
src/mcp9808/pyupm_mcp9808.i
Normal file
9
src/mcp9808/pyupm_mcp9808.i
Normal file
@ -0,0 +1,9 @@
|
||||
%module pyupm_mcp9808
|
||||
%include "../upm.i"
|
||||
|
||||
%feature("autodoc", "3");
|
||||
|
||||
%include "mcp9808.h"
|
||||
%{
|
||||
#include "mcp9808.h"
|
||||
%}
|
Loading…
x
Reference in New Issue
Block a user