Skip to content

Commit

Permalink
added some nullptr validations and improved init
Browse files Browse the repository at this point in the history
  • Loading branch information
hpsaturn committed Jul 16, 2023
1 parent 77e601a commit acdccaa
Show file tree
Hide file tree
Showing 2 changed files with 13 additions and 11 deletions.
18 changes: 12 additions & 6 deletions src/Sensors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -552,9 +552,9 @@ float Sensors::getUnitValue(UNIT unit) {
case GAS:
return gas;
case CPM:
return rad->getTics();
return getGeigerCPM();
case RAD:
return rad->getUSvh();
return getGeigerMicroSievertHour();
case NH3:
return nh3;
case CO:
Expand Down Expand Up @@ -1649,13 +1649,13 @@ void Sensors::resetAllVariables() {
pres = 0.0;
nh3 = 0;
co = 0;
rad->clear();
if (rad !=nullptr) rad->clear();
}

// #########################################################################

void Sensors::geigerRead(){
if(rad->read()){
if(rad !=nullptr && rad->read()){
unitRegister(UNIT::CPM);
unitRegister(UNIT::RAD);
}
Expand All @@ -1666,16 +1666,22 @@ void Sensors::geigerRead(){
*/
void Sensors::enableGeigerSensor(int gpio){
sensorAnnounce(SENSORS::SCAJOE);
if (gpio < 0) {
if (devmode) Serial.printf("[W][SLIB] undefined Geiger pin\t: %i\r\t", gpio);
return;
}
rad = new GEIGER(gpio,devmode);
sensorRegister(SENSORS::SCAJOE);
}

uint32_t Sensors::getGeigerCPM(void) {
return rad->getTics();
if (rad == nullptr) return 0;
else return rad->getTics();
}

float Sensors::getGeigerMicroSievertHour(void) {
return rad->getUSvh();
if (rad == nullptr) return 0;
else return rad->getUSvh();
}

// #########################################################################
Expand Down
6 changes: 1 addition & 5 deletions src/drivers/geiger.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,11 +31,7 @@ void IRAM_ATTR onGeigerTimer() {
// #########################################################################
// Initialize Geiger counter
GEIGER::GEIGER(int gpio, bool debug) {
#ifdef ESP32
if (gpio < 0) {
if (debug) Serial.println("[E][SLIB] undefined Geiger pin");
return;
}
#ifdef ESP32
devmode = debug;
tics_cnt = 0U; // tics in 1000ms
tics_tot = 0U; // total tics since boot
Expand Down

0 comments on commit acdccaa

Please sign in to comment.