mirror of
https://github.com/RobTillaart/Arduino.git
synced 2024-10-03 18:09:02 -04:00
0.2.2 MTP40C
This commit is contained in:
parent
31ec3d648f
commit
4bcd11b45d
@ -1,11 +1,27 @@
|
||||
platforms:
|
||||
rpipico:
|
||||
board: rp2040:rp2040:rpipico
|
||||
package: rp2040:rp2040
|
||||
gcc:
|
||||
features:
|
||||
defines:
|
||||
- ARDUINO_ARCH_RP2040
|
||||
warnings:
|
||||
flags:
|
||||
|
||||
packages:
|
||||
rp2040:rp2040:
|
||||
url: https://github.com/earlephilhower/arduino-pico/releases/download/global/package_rp2040_index.json
|
||||
|
||||
compile:
|
||||
# Choosing to run compilation tests on 2 different Arduino platforms
|
||||
platforms:
|
||||
- uno
|
||||
- due
|
||||
- zero
|
||||
- leonardo
|
||||
# - due
|
||||
# - zero
|
||||
# - leonardo
|
||||
- m4
|
||||
- esp32
|
||||
# - esp8266
|
||||
# - mega2560
|
||||
- rpipico
|
||||
|
32
libraries/MTP40C/CHANGELOG.md
Normal file
32
libraries/MTP40C/CHANGELOG.md
Normal file
@ -0,0 +1,32 @@
|
||||
# Change Log MTP40C
|
||||
|
||||
All notable changes to this project will be documented in this file.
|
||||
|
||||
The format is based on [Keep a Changelog](http://keepachangelog.com/)
|
||||
and this project adheres to [Semantic Versioning](http://semver.org/).
|
||||
|
||||
|
||||
## [0.2.2] - 2022-11-17
|
||||
- add RP2040 in build-CI
|
||||
- add changelog.md
|
||||
|
||||
|
||||
## [0.2.1] - 2021-12-22
|
||||
- update library.json
|
||||
- update license
|
||||
- minor edits
|
||||
|
||||
|
||||
## [0.2.0] - 2021-08-27
|
||||
- add MTP40D derived class
|
||||
- many fixes after testing
|
||||
|
||||
----
|
||||
|
||||
## [0.1.1] - 2021-08-23
|
||||
- addexamples
|
||||
- minor fixes
|
||||
|
||||
## [0.1.0] - 2021-08-20
|
||||
- initial version.
|
||||
|
@ -1,23 +1,17 @@
|
||||
//
|
||||
// FILE: MTP40C.h
|
||||
// FILE: MTP40C.cpp
|
||||
// AUTHOR: Rob Tillaart
|
||||
// DATE: 2021-08-20
|
||||
// VERSION: 0.2.1
|
||||
// VERSION: 0.2.2
|
||||
// PURPOSE: Arduino library for MTP40C MTP40D CO2 sensor
|
||||
// URL: https://github.com/RobTillaart/MTP40C
|
||||
//
|
||||
// HISTORY:
|
||||
// 0.1.0 2021-08-20 initial version
|
||||
// 0.1.1 2021-08-23 added examples, minor fixes
|
||||
// 0.2.0 2021-08-27 added MTP40D derived class
|
||||
// + many fixes after testing
|
||||
// 0.2.1 2021-12-22 update library.json, license, minor edits
|
||||
|
||||
|
||||
|
||||
#include "MTP40C.h"
|
||||
|
||||
// debug flag, development.
|
||||
// #define MTP40_DEBUG 1
|
||||
// debug flag, development.
|
||||
// #define MTP40_DEBUG 1
|
||||
|
||||
|
||||
|
||||
@ -90,7 +84,7 @@ float MTP40::getAirPressureReference()
|
||||
|
||||
_lastError = MTP40_OK;
|
||||
|
||||
// max read freq 1x per 4 seconds
|
||||
// max read freq 1x per 4 seconds
|
||||
if (millis() - _lastRead < 4000) return _airPressureReference; // last value
|
||||
_lastRead = millis();
|
||||
|
||||
@ -137,7 +131,6 @@ bool MTP40::setAirPressureReference(float apr)
|
||||
|
||||
uint16_t MTP40::getGasConcentration()
|
||||
{
|
||||
|
||||
_lastError = MTP40_OK;
|
||||
|
||||
// max read freq 1x per 4 seconds
|
||||
@ -266,20 +259,20 @@ int MTP40::lastError()
|
||||
|
||||
//////////////////////////////////////////////////////////////////////
|
||||
//
|
||||
// PRIVATE
|
||||
// PRIVATE
|
||||
//
|
||||
bool MTP40::request(uint8_t *data, uint8_t commandLength, uint8_t answerLength)
|
||||
{
|
||||
// generic or specific address
|
||||
// generic or specific address
|
||||
if (_useAddress)
|
||||
{
|
||||
data[0] = _address;
|
||||
}
|
||||
else
|
||||
{
|
||||
data[0] = 0xFE; // broadcast
|
||||
data[0] = 0xFE; // broadcast
|
||||
}
|
||||
// calculate CRC of command
|
||||
// calculate CRC of command
|
||||
uint16_t crc = CRC(data, commandLength - 2);
|
||||
data[commandLength - 1] = crc / 256;
|
||||
data[commandLength - 2] = crc & 0xFF;
|
||||
@ -292,7 +285,7 @@ bool MTP40::request(uint8_t *data, uint8_t commandLength, uint8_t answerLength)
|
||||
#else
|
||||
_ser->write(*data++);
|
||||
#endif
|
||||
yield(); // because baud rate is low!
|
||||
yield(); // because baud rate is low!
|
||||
}
|
||||
|
||||
uint32_t start = millis();
|
||||
@ -306,7 +299,7 @@ bool MTP40::request(uint8_t *data, uint8_t commandLength, uint8_t answerLength)
|
||||
i++;
|
||||
answerLength--;
|
||||
}
|
||||
yield(); // because baud rate is low!
|
||||
yield(); // because baud rate is low!
|
||||
}
|
||||
return true;
|
||||
}
|
||||
@ -363,9 +356,9 @@ const uint8_t auchCRCLo[] = {
|
||||
uint16_t uIndex; // Query the CRC table index
|
||||
uint16_t crc;
|
||||
|
||||
while (len--) /* Complete the entire message buffer*/
|
||||
while (len--) /* Complete the entire message buffer*/
|
||||
{
|
||||
uIndex = uchCRCLo ^ *data++; /* Calculate CRC */;
|
||||
uIndex = uchCRCLo ^ *data++; /* Calculate CRC */;
|
||||
uchCRCLo = uchCRCHi ^ auchCRCHi[uIndex];
|
||||
uchCRCHi = auchCRCLo[uIndex];
|
||||
}
|
||||
@ -377,7 +370,7 @@ const uint8_t auchCRCLo[] = {
|
||||
|
||||
/////////////////////////////////////////////////////////////
|
||||
//
|
||||
// DERIVED CLASSES
|
||||
// DERIVED CLASSES
|
||||
//
|
||||
|
||||
MTP40C::MTP40C(Stream * str) : MTP40(str)
|
||||
|
@ -3,12 +3,11 @@
|
||||
// FILE: MTP40C.h
|
||||
// AUTHOR: Rob Tillaart
|
||||
// DATE: 2021-08-20
|
||||
// VERSION: 0.2.1
|
||||
// VERSION: 0.2.2
|
||||
// PURPOSE: Arduino library for MTP40C + MTP40D CO2 sensor
|
||||
// URL: https://github.com/RobTillaart/MTP40C
|
||||
//
|
||||
// HISTORY:
|
||||
// see MTP40C.cpp file
|
||||
// HISTORY: see changelog.md
|
||||
//
|
||||
// Based upon datasheet June 2020, version 2.0
|
||||
//
|
||||
@ -17,7 +16,7 @@
|
||||
#include "Arduino.h"
|
||||
|
||||
|
||||
#define MTP40_LIB_VERSION (F("0.2.1"))
|
||||
#define MTP40_LIB_VERSION (F("0.2.2"))
|
||||
|
||||
|
||||
#define MTP40_DEFAULT_ADDRESS 0x64
|
||||
@ -62,13 +61,14 @@ public:
|
||||
void setSpecificAddress() { _useAddress = true; };
|
||||
bool useSpecificAddress() { return _useAddress; };
|
||||
|
||||
// set timeout of serial communication.
|
||||
// set timeout of serial communication.
|
||||
void setTimeout(uint32_t to = 100) { _timeout = to; };
|
||||
uint32_t getTimeout() { return _timeout; };
|
||||
|
||||
uint32_t lastRead() { return _lastRead; };
|
||||
|
||||
// 2 = MTP40C 3 = MTP40D
|
||||
// 2 = MTP40C
|
||||
// 3 = MTP40D
|
||||
uint8_t getType() { return _type; };
|
||||
int lastError();
|
||||
|
||||
|
@ -204,6 +204,11 @@ moments. Valid values are 24 - 720 .
|
||||
- **uint16_t getSelfCalibrationHours()** returns the value set above.
|
||||
|
||||
|
||||
## Operations
|
||||
|
||||
See examples.
|
||||
|
||||
|
||||
## Future
|
||||
|
||||
#### CRC
|
||||
@ -223,11 +228,7 @@ moments. Valid values are 24 - 720 .
|
||||
|
||||
- serial bus with multiple devices? => diodes
|
||||
- improve readability code (e.g. parameter names)
|
||||
|
||||
|
||||
## Operations
|
||||
|
||||
See examples.
|
||||
- move all code from .h to .cpp file
|
||||
|
||||
|
||||
## Sponsor
|
||||
|
@ -15,7 +15,7 @@
|
||||
"type": "git",
|
||||
"url": "https://github.com/RobTillaart/MTP40C.git"
|
||||
},
|
||||
"version": "0.2.1",
|
||||
"version": "0.2.2",
|
||||
"license": "MIT",
|
||||
"frameworks": "arduino",
|
||||
"platforms": "*",
|
||||
|
@ -1,5 +1,5 @@
|
||||
name=MTP40C
|
||||
version=0.2.1
|
||||
version=0.2.2
|
||||
author=Rob Tillaart <rob.tillaart@gmail.com>
|
||||
maintainer=Rob Tillaart <rob.tillaart@gmail.com>
|
||||
sentence=Arduino library for MTP40, MTP40C and MTP40D CO2 sensor
|
||||
|
@ -35,10 +35,10 @@
|
||||
|
||||
////////////////////////////////////
|
||||
//
|
||||
// MANY TESTS WILL BLOCK AS BUILD CI HAS NO GOOD TIMEOUT
|
||||
// ALL FAILING TESTS ARE COMMENTED
|
||||
// MANY TESTS WILL BLOCK AS BUILD CI HAS NO GOOD TIMEOUT
|
||||
// ALL FAILING TESTS ARE COMMENTED
|
||||
//
|
||||
// USE GODMODE SERIAL TO IMPROVE THESE TESTS
|
||||
// USE GODMODE SERIAL TO IMPROVE THESE TESTS
|
||||
//
|
||||
|
||||
#include <ArduinoUnitTests.h>
|
||||
|
Loading…
Reference in New Issue
Block a user