Stima V4 Slave RAIN  4.2
elaborate_data_task.cpp
Go to the documentation of this file.
1 
31 #define TRACE_LEVEL ELABORATE_DATA_TASK_TRACE_LEVEL
32 #define LOCAL_TASK_ID ELABORATE_TASK_ID
33 
35 
36 using namespace cpp_freertos;
37 
43 ElaborateDataTask::ElaborateDataTask(const char *taskName, uint16_t stackSize, uint8_t priority, ElaborateDataParam_t elaborateDataParam) : Thread(taskName, stackSize, priority), param(elaborateDataParam)
44 {
45  // Start WDT controller and TaskState Flags
48 
50  Start();
51 };
52 
53 #if (ENABLE_STACK_USAGE)
55 void ElaborateDataTask::TaskMonitorStack()
56 {
57  uint16_t stackUsage = (uint16_t)uxTaskGetStackHighWaterMark( NULL );
58  if((stackUsage) && (stackUsage < param.system_status->tasks[LOCAL_TASK_ID].stack)) {
59  param.systemStatusLock->Take();
61  param.systemStatusLock->Give();
62  }
63 }
64 #endif
65 
68 void ElaborateDataTask::TaskWatchDog(uint32_t millis_standby)
69 {
70  // Local TaskWatchDog update
71  param.systemStatusLock->Take();
72  // Update WDT Signal (Direct or Long function Timered)
73  if(millis_standby)
74  {
75  // Check 1/2 Freq. controller ready to WDT only SET flag
76  if((millis_standby) < WDT_CONTROLLER_MS / 2) {
78  } else {
80  // Add security milimal Freq to check
82  }
83  }
84  else
86  param.systemStatusLock->Give();
87 }
88 
93 void ElaborateDataTask::TaskState(uint8_t state_position, uint8_t state_subposition, task_flag state_operation)
94 {
95  // Local TaskWatchDog update
96  param.systemStatusLock->Take();
97  // Signal Task sleep/disabled mode from request (Auto SET WDT on Resume)
99  (state_operation==task_flag::normal))
101  param.system_status->tasks[LOCAL_TASK_ID].state = state_operation;
103  param.system_status->tasks[LOCAL_TASK_ID].running_sub = state_subposition;
104  param.systemStatusLock->Give();
105 }
106 
109  // Queue for data
110  elaborate_data_t edata;
111  request_data_t request_data;
112  // System message data queue structured
113  system_message_t system_message;
114 
115  uint8_t edata_cmd; // command function to elaborate data queue
116 
117  // Start Running Monitor and First WDT normal state
118  #if (ENABLE_STACK_USAGE)
119  TaskMonitorStack();
120  #endif
122 
123  // Init scrolling TPR timings and buffer data
124  // Maintenance not performed (automatic checked in rain_task)
126  bufferReset<sample_t, uint16_t, rmapdata_t>(&rain_samples, SAMPLES_COUNT_MAX);
127  uint32_t next_ms_buffer_check = millis() + SAMPLES_ACQUIRE_MS;
128  uint32_t request_data_init_ms = millis();
129  uint32_t sec_from_elaborate_start = 0;
130 
131  // Init real and last elaborate data response variables
132  memset(&report, 0, sizeof(report_t));
133  memset(&report_last, 0, sizeof(report_t));
134 
135  while (true) {
136 
137  // Elaborate scrolling XX required defined msec.
138  if(millis() >= next_ms_buffer_check) {
139  // Sec from starting (check valid RMAP data response timing when minimal data acquire is ready)
140  sec_from_elaborate_start += SAMPLES_ACQUIRE_MS / 1000;
141  next_ms_buffer_check += SAMPLES_ACQUIRE_MS;
142  // ? over roll and security check timer area into reset check ms expected
143  if (labs(millis() - next_ms_buffer_check) > SAMPLES_ACQUIRE_MS) {
144  next_ms_buffer_check = millis() + SAMPLES_ACQUIRE_MS;
145  }
146  // Add current scrolling data to buffer
147  addValue<sample_t, uint16_t, rmapdata_t>(&rain_samples, SAMPLES_COUNT_MAX, rain_elaborate.rain_scroll);
148  // Perform reset on rain task. Security local new ungetted data rain.rain_scroll to 0
150  edata_cmd = RAIN_SCROLL_RESET;
151  param.rainQueue->Enqueue(&edata_cmd, Ticks::MsToTicks(WAIT_QUEUE_REQUEST_RESET_TIP_MS));
152  }
153 
154  // ********* SYSTEM QUEUE MESSAGE ***********
155  // enqueud system message from caller task
156  if (!param.systemMessageQueue->IsEmpty()) {
157  // Read queue in test mode
158  if (param.systemMessageQueue->Peek(&system_message, 0))
159  {
160  // Its request addressed into ALL TASK... -> no pull (only SUPERVISOR or external gestor)
161  if(system_message.task_dest == ALL_TASK_ID)
162  {
163  // Pull && elaborate command,
164  if(system_message.command.do_sleep)
165  {
166  // Enter sleep module OK and update WDT
169  Delay(Ticks::MsToTicks(ELABORATE_TASK_SLEEP_DELAY_MS));
171  }
172  }
173  }
174  }
175 
176  // enqueud from rain sensors task (populate data)
177  if (!param.elaborateDataQueue->IsEmpty()) {
178  if (param.elaborateDataQueue->Peek(&edata, 0))
179  {
180  param.elaborateDataQueue->Dequeue(&edata);
181  switch (edata.index)
182  {
183  case RAIN_TIPS_INDEX:
184  TRACE_VERBOSE_F(F("Rain tips: %d\r\n"), edata.value);
185  rain_elaborate.tips_count = (uint16_t)edata.value;
186  break;
187 
188  case RAIN_RAIN_INDEX:
189  TRACE_VERBOSE_F(F("Rain: %d\r\n"), edata.value);
190  rain_elaborate.rain = (uint16_t)edata.value;
191  break;
192 
193  case RAIN_FULL_INDEX:
194  TRACE_VERBOSE_F(F("Rain full: %d\r\n"), edata.value);
195  rain_elaborate.rain_full = (uint16_t)edata.value;
196  break;
197 
198  case RAIN_SCROLL_INDEX:
199  TRACE_VERBOSE_F(F("Rain scroll: %d\r\n"), edata.value);
200  rain_elaborate.rain_scroll = (uint16_t)edata.value;
201  break;
202  }
203  }
204  }
205 
206  // enqueued from can task (get data, start command...)
207  if (!param.requestDataQueue->IsEmpty()) {
208  // Read request immediatly if queue is not empty
209  if (param.requestDataQueue->Dequeue(&request_data))
210  {
211  // ? over roll and security check timer area into reset check ms expected
212  // Report request is too fast (<REPORT_INVALID_ACQUIRE_MIN_MS) ... N.B. When are in Command retry!
213  // Initialize value if command retry is also executed (before) but result data can be resetted
214  // Need to save older value and retry value must are older value (only in retry command)
215  // After timing retry command, value data report is ok and newver resetted value can be sended
216  if (request_data.is_init) {
217  // ? Request valid (last init request > REPORT_INVALID_ACQUIRE_MIN_MS)
218  if (labs(millis() - request_data_init_ms) > REPORT_INVALID_ACQUIRE_MIN_MS) {
219  // test if minimal data acquire are valid
220  bool min_percentage_acquire = false;
221  if (sec_from_elaborate_start < request_data.report_time_s) {
222  if(((((float)sec_from_elaborate_start / (float)request_data.report_time_s)) * 100.0) < SAMPLE_ERROR_PERCENTAGE_MIN) {
223  min_percentage_acquire = true;
224  }
225  }
226  if(!min_percentage_acquire) {
227  // Coerent value, generate report
228  make_report(request_data.report_time_s, request_data.observation_time_s);
229  } else {
230  // Error timing not full, void report
231  report.quality = RMAPDATA_MAX;
232  report.rain = RMAPDATA_MAX;
233  report.rain_full = RMAPDATA_MAX;
234  report.rain_tpr_05m_avg = RMAPDATA_MAX;
235  report.rain_tpr_60s_avg = RMAPDATA_MAX;
236  report.tips_count = RMAPDATA_MAX;
237  }
238  // Saving data before reset index and scrolling value (Need for possible retry...)
240  // Response with new value (resetted ore istant value. No retry command Here)
241  param.reportDataQueue->Enqueue(&report);
242 
243  // Save timing for report request and with init index value for saving remote data
244  request_data_init_ms = millis();
245 
246  // Forced reset index internal (internal index are updated only with queue on event from rain)
247  // If no event occurs the queue would not fill and the value would remain the previous one
250  rain_elaborate.rain = 0;
252 
253  // Perform reset on rain task (event = false) No Event of Rain. (Other incoming Request)
254  edata_cmd = RAIN_TIPS_RESET;
255  param.rainQueue->Enqueue(&edata_cmd, Ticks::MsToTicks(WAIT_QUEUE_REQUEST_RESET_TIP_MS));
256 
257  } else {
258  // Response with older value (Retry command Here without reinit command also called up)
259  param.reportDataQueue->Enqueue(&report_last);
260  }
261  } else {
262  // Response with new value (istant value. Unused retry command Here)
263  make_report(request_data.report_time_s, request_data.observation_time_s);
264  param.reportDataQueue->Enqueue(&report);
265  }
266  }
267  }
268 
269  #if (ENABLE_STACK_USAGE)
270  TaskMonitorStack();
271  #endif
272 
273  // Local TaskWatchDog update;
275 
276  DelayUntil(Ticks::MsToTicks(ELABORATE_TASK_WAIT_DELAY_MS));
277  }
278 }
279 
283  float quality = 100.0;
284  bool bIsClogged;
285 
286  #if (USE_CLOGGED_UP_CONTROL)
287  // Checking signal CLOGGED_UP (on Event or Reset... remote calling)
288  #if (CLOGGED_EVENT_VALUE)
289  bIsClogged = digitalRead(CLOGGED_UP_PIN);
290  #else
291  bIsClogged = !digitalRead(CLOGGED_UP_PIN);
292  #endif
293  param.systemStatusLock->Take();
294  if(bIsClogged) {
296  // Check event for real alarm set value
299  }
300  } else {
301  // Start alert flags
304  }
305  } else {
306  // Restore alert flag
309  }
310  param.systemStatusLock->Give();
311  if(bIsClogged) {
312  TRACE_INFO_F(F("Sensor: ALERT read status of clogged up... [ ALARM: %d ]\r\n"), param.system_status->events.is_clogged_up);
313  }
314  #endif
315 
317  quality = 0.0;
318  } else {
320  quality -= param.system_status->events.error_count; // 1 Error = -1%
321  if(quality<0.0) quality = 0.0;
322  }
323  // Reduce 15% for error on one reed
324  if(param.system_status->events.is_main_error) quality *= 0.85;
325  if(param.system_status->events.is_redundant_error) quality *= 0.85;
326  // Reduce 30% on error bubble_level (if accelerometr working correctly)
328  (param.system_status->events.is_bubble_level_error)) quality *= 0.7;
329  }
330  return (uint8_t) quality;
331 }
332 
336 void ElaborateDataTask::make_report(uint16_t report_time_s, uint8_t observation_time_s)
337 {
338  #if (USE_MOBILE_TPR_60_S_AVG_MODE)
339  uint16_t rain_buf_60s[SAMPLES_NEED_TPR_60_S] = {0}; // Scroll buffer for max on 60 sec
340  #endif
341  uint16_t rain_ist; // Istant buffered data on 10 sec
342  uint16_t rain_sum_60s = 0; // current sum on 60 sec
343  uint16_t rain_sum_60s_max = 0; // max sum on mobile window of 60 sec.
344  uint16_t rain_sum_05m = 0; // current sum on 5 min
345  uint16_t rain_sum_05m_max = 0; // max sum on fixed window of 5 min.
346 
347  float valid_data_calc_perc; // Shared calculate valid % of measure (Data Valid or not?)
348  uint16_t n_sample = 0; // Sample elaboration number... (incremented on calc development)
349  bool is_05m_sample_valid = false; // True if sample 05 min is valid (1 sample complete min)
350 
351  // Elaboration timings calculation (fix 5Min to TPR 5 Min, Fix 60 Sec to TPR 60 Sec)
352  uint16_t report_sample_count = round((report_time_s * 1.0) / (SAMPLES_ACQUIRE_MS / 1000.0));
353  uint16_t observation_sample_count = round((observation_time_s * 1.0) / (SAMPLES_ACQUIRE_MS / 1000.0));
354 
355  // Request to calculate is correct? Trace request
356  if (report_time_s == 0)
357  {
358  // Request an direct sample value for istant measure
359  TRACE_INFO_F(F("Elaborate: Requested an istant value\r\n"));
360  }
361  else
362  {
363  TRACE_INFO_F(F("Elaborate: Requested an report on %d seconds\r\n"), report_time_s);
364  TRACE_DEBUG_F(F("-> %d samples counts need for report\r\n"), report_sample_count);
365  TRACE_DEBUG_F(F("-> %d samples counts need for observation\r\n"), observation_sample_count);
366  TRACE_DEBUG_F(F("-> %d available rain samples count\r\n"), rain_samples.count);
367  }
368 
369  // Default value to RMAP Limit error value
370  report.rain_tpr_60s_avg = RMAPDATA_MAX;
371  report.rain_tpr_05m_avg = RMAPDATA_MAX;
372 
373  // Ptr for value sample
374  bufferPtrResetBack<sample_t, uint16_t>(&rain_samples, SAMPLES_COUNT_MAX);
375 
376  // align all sensor's data to last common acquired sample
377  uint16_t samples_count = rain_samples.count;
378 
379  // No need ... it's a simple istant or report request?
380  for (uint16_t i = 0; i < samples_count; i++)
381  {
382  // Calculate rain rate on 60" mobile to report timing area
383  // End of Sample in calculation (Completed with the request... Exit on Full Buffer ReadBack executed)
384  if(n_sample >= report_sample_count) break;
385 
386  // Reading data ist from buffered value
387  rain_ist = bufferReadBack<sample_t, uint16_t, rmapdata_t>(&rain_samples, SAMPLES_COUNT_MAX);
388  n_sample++;
389 
390  #if (USE_MOBILE_TPR_60_S_AVG_MODE)
391  // Scrolling older value on timing observation value area
392  for(uint8_t rr_idx = (SAMPLES_NEED_TPR_60_S - 1); rr_idx > 0; rr_idx--) {
393  rain_buf_60s[rr_idx] = rain_buf_60s[rr_idx-1];
394  }
395  rain_buf_60s[0] = rain_ist;
396  // Calculate SUM on timing obeservation in mobile mode
397  rain_sum_60s = 0;
398  for(uint8_t rr_idx = 0; rr_idx < SAMPLES_NEED_TPR_60_S; rr_idx++) {
399  rain_sum_60s += rain_buf_60s[rr_idx];
400  }
401  if(rain_sum_60s > rain_sum_60s_max) rain_sum_60s_max = rain_sum_60s;
402  #else
403  // Populate buffer SUM on 60 sec - Fixed Calculate MAX on 60 SEC
404  rain_sum_60s += rain_ist;
405  if((n_sample % SAMPLES_NEED_TPR_60_S)==0) {
406  // Calculate MAX of SUM and reinit for next timing check
407  if(rain_sum_60s > rain_sum_60s_max) rain_sum_60s_max = rain_sum_60s;
408  rain_sum_60s = 0;
409  }
410  #endif
411 
412  // Populate buffer SUM on 5 MIN - Fixed Calculate MAX on 5 MIN
413  rain_sum_05m += rain_ist;
414  if((n_sample % SAMPLES_NEED_TPR_05_M)==0) {
415  is_05m_sample_valid = true;
416  // Calculate MAX of SUM and reinit for next timing check
417  if(rain_sum_05m > rain_sum_05m_max) rain_sum_05m_max = rain_sum_05m;
418  rain_sum_05m = 0;
419  }
420  }
421  // ***************************************************************************************************
422  // ******* GENERATE REPORT RESPONSE WITH ALL DATA AVAIABLE AND VALID WITH EXPECETD OBSERVATION *******
423  // ***************************************************************************************************
424 
428  report.quality = (rmapdata_t)checkRain();
429 
430  // rain TPR, elaboration final (if over number min sample)
431  valid_data_calc_perc = (float)(n_sample) / (float)(report_sample_count) * 100.0;
432  if (valid_data_calc_perc >= OBSERVATION_ERROR_PERCENTAGE_MIN)
433  {
434  // Use 10^4 rappresentation with 4 decimal
435  report.rain_tpr_60s_avg = (rmapdata_t)(((float)rain_sum_60s_max * (float)RAIN_RATE_MULTIPLY) / 60.0);
436  if(is_05m_sample_valid) {
437  report.rain_tpr_05m_avg = (rmapdata_t)(((float)rain_sum_05m_max * (float)RAIN_RATE_MULTIPLY) / 300.0);
438  }
439  }
440 }
441 
442 template <typename buffer_g, typename length_v, typename value_v>
443 value_v bufferRead(buffer_g *buffer, length_v length)
444 {
445  value_v value = *buffer->read_ptr;
446 
447  if (buffer->read_ptr == buffer->values+length-1) {
448  buffer->read_ptr = buffer->values;
449  }
450  else buffer->read_ptr++;
451 
452  return value;
453 }
454 
455 template <typename buffer_g, typename length_v, typename value_v>
456 value_v bufferReadBack(buffer_g *buffer, length_v length)
457 {
458  value_v value = *buffer->read_ptr;
459 
460  if (buffer->read_ptr == buffer->values) {
461  buffer->read_ptr = buffer->values+length-1;
462  }
463  else buffer->read_ptr--;
464 
465  return value;
466 }
467 
468 template <typename buffer_g, typename value_v>
469 void bufferWrite(buffer_g *buffer, value_v value)
470 {
471  *buffer->write_ptr = value;
472 }
473 
474 template <typename buffer_g>
475 void bufferPtrReset(buffer_g *buffer)
476 {
477  buffer->read_ptr = buffer->values;
478 }
479 
480 template <typename buffer_g, typename length_v>
481 void bufferPtrResetBack(buffer_g *buffer, length_v length)
482 {
483  if (buffer->write_ptr == buffer->values)
484  {
485  buffer->read_ptr = buffer->values+length-1;
486  }
487  else buffer->read_ptr = buffer->write_ptr-1;
488 }
489 
490 template <typename buffer_g, typename length_v>
491 void incrementBuffer(buffer_g *buffer, length_v length)
492 {
493  if (buffer->count < length)
494  {
495  buffer->count++;
496  }
497 
498  if (buffer->write_ptr+1 < buffer->values + length) {
499  buffer->write_ptr++;
500  } else buffer->write_ptr = buffer->values;
501 }
502 
503 template <typename buffer_g, typename length_v, typename value_v>
504 void bufferReset(buffer_g *buffer, length_v length)
505 {
506  memset(buffer->values, 0xFF, length * sizeof(value_v));
507  buffer->count = 0;
508  buffer->read_ptr = buffer->values;
509  buffer->write_ptr = buffer->values;
510 }
511 
512 template <typename buffer_g, typename length_v, typename value_v>
513 void addValue(buffer_g *buffer, length_v length, value_v value)
514 {
515  *buffer->write_ptr = (value_v)value;
516  incrementBuffer<buffer_g, length_v>(buffer, length);
517 }
void TaskState(uint8_t state_position, uint8_t state_subposition, task_flag state_operation)
local suspend flag and positor running state Task (optional)
uint8_t checkRain(void)
Check sensor Quality.
ElaborateDataParam_t param
void make_report(uint16_t report_time_s=REPORTS_TIME_S, uint8_t observation_time_s=OBSERVATIONS_TIME_S)
Create an RMAP report value.
void TaskWatchDog(uint32_t millis_standby)
local watchDog and Sleep flag Task (optional)
ElaborateDataTask(const char *taskName, uint16_t stackSize, uint8_t priority, ElaborateDataParam_t elaborateDataParam)
Construct the Elaborate Data Task::ElaborateDataTask object.
virtual void Run()
RUN Task.
#define RAIN_SCROLL_INDEX
Definition: config.h:251
#define WAIT_QUEUE_REQUEST_RESET_TIP_MS
Time to wait event reset get tips command.
Definition: config.h:190
#define RAIN_TIPS_INDEX
Definition: config.h:247
#define WDT_CONTROLLER_MS
Task milliseconds minimal check.
Definition: config.h:90
#define SAMPLES_NEED_TPR_60_S
Samples need for TPR over 1'.
Definition: config.h:242
#define REPORT_INVALID_ACQUIRE_MIN_MS
Minimal timing for 2 report calculate (less can be only a command retry)
Definition: config.h:238
#define ALL_TASK_ID
All task ID. Send message to ALL Task.
Definition: config.h:166
#define OBSERVATION_ERROR_PERCENTAGE_MIN
Observation min percent valid on elaboration data.
Definition: config.h:264
#define SAMPLES_NEED_TPR_05_M
Samples need for TPR over 5'.
Definition: config.h:244
#define RAIN_RATE_MULTIPLY
RMAP Multiply value for TPR Elaboration.
Definition: config.h:259
#define CLOGGED_UP_PIN
Clogged Up Alert PIN.
Definition: config.h:217
#define WDT_STARTING_TASK_MS
Init WatchDog Task local milliseconds.
Definition: config.h:88
#define RAIN_RAIN_INDEX
Definition: config.h:248
#define RAIN_SCROLL_RESET
Definition: config.h:252
#define RAIN_FULL_INDEX
Definition: config.h:249
#define RAIN_TIPS_RESET
Definition: config.h:250
#define SAMPLES_COUNT_MAX
Sample and default value for elaborate task.
Definition: config.h:225
#define SAMPLES_ACQUIRE_MS
Timing for acquire and check TPR elaboration.
Definition: config.h:240
#define UNUSED_SUB_POSITION
Monitor Sub Position not used flag.
Definition: config.h:94
#define SAMPLE_ERROR_PERCENTAGE_MIN
Samples min percent valid on elaboration data.
Definition: config.h:262
#define TRACE_DEBUG_F(...)
Definition: debug_F.h:63
#define TRACE_INFO_F(...)
Definition: debug_F.h:57
#define TRACE_VERBOSE_F(...)
Definition: debug_F.h:71
void incrementBuffer(buffer_g *buffer, length_v length)
void bufferPtrResetBack(buffer_g *buffer, length_v length)
#define LOCAL_TASK_ID
void bufferPtrReset(buffer_g *buffer)
value_v bufferRead(buffer_g *buffer, length_v length)
void bufferReset(buffer_g *buffer, length_v length)
void bufferWrite(buffer_g *buffer, value_v value)
void addValue(buffer_g *buffer, length_v length, value_v value)
value_v bufferReadBack(buffer_g *buffer, length_v length)
Elaborate data sensor to CAN header file.
#define CLOGGED_TIMINGS_VERIFY
#define ELABORATE_TASK_SLEEP_DELAY_MS
#define ELABORATE_TASK_WAIT_DELAY_MS
@ set
Set WDT (From Application TASK... All OK)
Definition: local_typedef.h:60
@ timer
Set Timered WDT (From Application long function WDT...)
Definition: local_typedef.h:61
task_flag
Task state Flag type.
Definition: local_typedef.h:65
@ suspended
Task is excluded from WDT Controller or Suspended complete.
Definition: local_typedef.h:68
@ sleepy
Task is in sleep mode or longer wait (Inform WDT controller)
Definition: local_typedef.h:67
@ normal
Normal operation Task controller.
Definition: local_typedef.h:66
struct local elaborate data parameter
cpp_freertos::Queue * systemMessageQueue
Queue for system message.
cpp_freertos::Queue * elaborateDataQueue
Queue for elaborate data.
system_status_t * system_status
system status pointer struct
cpp_freertos::Queue * rainQueue
Queue to RAIN Event.
cpp_freertos::BinarySemaphore * systemStatusLock
semaphore access to system status
cpp_freertos::Queue * requestDataQueue
Queue for request data.
cpp_freertos::Queue * reportDataQueue
Queue for report data.
rmapdata_t tips_full
Number of tips readed (With Maintenance value, for Display LCD)
rmapdata_t rain
Rain official (without Maintenance value)
rmapdata_t rain_full
Rain unofficial (With Maintenance value, for Display LCD)
rmapdata_t rain_scroll
Rain scrolling for step TPR calculation (without Maintenance value)
rmapdata_t tips_count
Number of tips readed (without Maintenance value)
Report module.
rmapdata_t rain
Rain official (without Maintenance value)
rmapdata_t rain_full
Rain unofficial (With Maintenance value, for Display LCD)
rmapdata_t rain_tpr_60s_avg
Rain official (TPR on 1')
rmapdata_t quality
Rain quality of measure.
rmapdata_t tips_count
Number of tips readed (without Maintenance value)
rmapdata_t rain_tpr_05m_avg
Rain official (TPR on 5')
uint16_t count
samples counter
System message for queue.
uint8_t task_dest
Command struct.
uint8_t do_sleep
Optional param for difference level Sleep.
struct system_message_t::@7 command
bool is_clogged_up
Sensor is clogged up.
struct system_status_t::@6 running
uint32_t epoch_clogged_up
Sensor is clogged up epoch event start.
bool is_main_error
Main sensor in error.
uint16_t error_count
Count of error event.
struct system_status_t::@5 events
Module error or alert timings continuos verify.
bool clogged_up
Sensor is clogged up.
task_t tasks[TOTAL_INFO_TASK]
Info Task && WDT.
Definition: local_typedef.h:92
bool is_bubble_level_error
Bubble software accelerometer error.
bool is_redundant_error
Redundant sensor in error.
bool is_tipping_error
Tipping event error run.
bool is_accelerometer_error
Accelerometer error.
int32_t watch_dog_ms
WatchDog of Task Timer.
Definition: local_typedef.h:75
uint8_t running_pos
!=0 (CREATE) Task Started (Generic state of Task)
Definition: local_typedef.h:78
task_flag state
Long sleep Task.
Definition: local_typedef.h:77
wdt_flag watch_dog
WatchDog of Task.
Definition: local_typedef.h:74
uint16_t stack
Stack Max Usage Monitor.
Definition: local_typedef.h:76
uint8_t running_sub
Optional SubState of Task.
Definition: local_typedef.h:79