31 #define TRACE_LEVEL ELABORATE_DATA_TASK_TRACE_LEVEL
32 #define LOCAL_TASK_ID ELABORATE_TASK_ID
36 using namespace cpp_freertos;
53 #if (ENABLE_STACK_USAGE)
55 void ElaborateDataTask::TaskMonitorStack()
57 uint16_t stackUsage = (uint16_t)uxTaskGetStackHighWaterMark( NULL );
110 elaborate_data_t edata;
111 request_data_t request_data;
118 #if (ENABLE_STACK_USAGE)
128 uint32_t request_data_init_ms = millis();
129 uint32_t sec_from_elaborate_start = 0;
138 if(millis() >= next_ms_buffer_check) {
216 if (request_data.is_init) {
220 bool min_percentage_acquire =
false;
221 if (sec_from_elaborate_start < request_data.report_time_s) {
223 min_percentage_acquire =
true;
226 if(!min_percentage_acquire) {
228 make_report(request_data.report_time_s, request_data.observation_time_s);
244 request_data_init_ms = millis();
263 make_report(request_data.report_time_s, request_data.observation_time_s);
269 #if (ENABLE_STACK_USAGE)
283 float quality = 100.0;
286 #if (USE_CLOGGED_UP_CONTROL)
288 #if (CLOGGED_EVENT_VALUE)
321 if(quality<0.0) quality = 0.0;
330 return (uint8_t) quality;
338 #if (USE_MOBILE_TPR_60_S_AVG_MODE)
342 uint16_t rain_sum_60s = 0;
343 uint16_t rain_sum_60s_max = 0;
344 uint16_t rain_sum_05m = 0;
345 uint16_t rain_sum_05m_max = 0;
347 float valid_data_calc_perc;
348 uint16_t n_sample = 0;
349 bool is_05m_sample_valid =
false;
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));
356 if (report_time_s == 0)
359 TRACE_INFO_F(F(
"Elaborate: Requested an istant value\r\n"));
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);
380 for (uint16_t i = 0; i < samples_count; i++)
384 if(n_sample >= report_sample_count)
break;
390 #if (USE_MOBILE_TPR_60_S_AVG_MODE)
393 rain_buf_60s[rr_idx] = rain_buf_60s[rr_idx-1];
395 rain_buf_60s[0] = rain_ist;
399 rain_sum_60s += rain_buf_60s[rr_idx];
401 if(rain_sum_60s > rain_sum_60s_max) rain_sum_60s_max = rain_sum_60s;
404 rain_sum_60s += rain_ist;
407 if(rain_sum_60s > rain_sum_60s_max) rain_sum_60s_max = rain_sum_60s;
413 rain_sum_05m += rain_ist;
415 is_05m_sample_valid =
true;
417 if(rain_sum_05m > rain_sum_05m_max) rain_sum_05m_max = rain_sum_05m;
431 valid_data_calc_perc = (float)(n_sample) / (float)(report_sample_count) * 100.0;
436 if(is_05m_sample_valid) {
442 template <
typename buffer_g,
typename length_v,
typename value_v>
445 value_v value = *buffer->read_ptr;
447 if (buffer->read_ptr == buffer->values+length-1) {
448 buffer->read_ptr = buffer->values;
450 else buffer->read_ptr++;
455 template <
typename buffer_g,
typename length_v,
typename value_v>
458 value_v value = *buffer->read_ptr;
460 if (buffer->read_ptr == buffer->values) {
461 buffer->read_ptr = buffer->values+length-1;
463 else buffer->read_ptr--;
468 template <
typename buffer_g,
typename value_v>
471 *buffer->write_ptr = value;
474 template <
typename buffer_g>
477 buffer->read_ptr = buffer->values;
480 template <
typename buffer_g,
typename length_v>
483 if (buffer->write_ptr == buffer->values)
485 buffer->read_ptr = buffer->values+length-1;
487 else buffer->read_ptr = buffer->write_ptr-1;
490 template <
typename buffer_g,
typename length_v>
493 if (buffer->count < length)
498 if (buffer->write_ptr+1 < buffer->values + length) {
500 }
else buffer->write_ptr = buffer->values;
503 template <
typename buffer_g,
typename length_v,
typename value_v>
506 memset(buffer->values, 0xFF, length *
sizeof(value_v));
508 buffer->read_ptr = buffer->values;
509 buffer->write_ptr = buffer->values;
512 template <
typename buffer_g,
typename length_v,
typename value_v>
513 void addValue(buffer_g *buffer, length_v length, value_v value)
515 *buffer->write_ptr = (value_v)value;
516 incrementBuffer<buffer_g, length_v>(buffer, length);
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
#define WAIT_QUEUE_REQUEST_RESET_TIP_MS
Time to wait event reset get tips command.
#define WDT_CONTROLLER_MS
Task milliseconds minimal check.
#define SAMPLES_NEED_TPR_60_S
Samples need for TPR over 1'.
#define REPORT_INVALID_ACQUIRE_MIN_MS
Minimal timing for 2 report calculate (less can be only a command retry)
#define ALL_TASK_ID
All task ID. Send message to ALL Task.
#define OBSERVATION_ERROR_PERCENTAGE_MIN
Observation min percent valid on elaboration data.
#define SAMPLES_NEED_TPR_05_M
Samples need for TPR over 5'.
#define RAIN_RATE_MULTIPLY
RMAP Multiply value for TPR Elaboration.
#define CLOGGED_UP_PIN
Clogged Up Alert PIN.
#define WDT_STARTING_TASK_MS
Init WatchDog Task local milliseconds.
#define RAIN_SCROLL_RESET
#define SAMPLES_COUNT_MAX
Sample and default value for elaborate task.
#define SAMPLES_ACQUIRE_MS
Timing for acquire and check TPR elaboration.
#define UNUSED_SUB_POSITION
Monitor Sub Position not used flag.
#define SAMPLE_ERROR_PERCENTAGE_MIN
Samples min percent valid on elaboration data.
#define TRACE_DEBUG_F(...)
#define TRACE_INFO_F(...)
#define TRACE_VERBOSE_F(...)
void incrementBuffer(buffer_g *buffer, length_v length)
void bufferPtrResetBack(buffer_g *buffer, length_v length)
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)
@ timer
Set Timered WDT (From Application long function WDT...)
task_flag
Task state Flag type.
@ suspended
Task is excluded from WDT Controller or Suspended complete.
@ sleepy
Task is in sleep mode or longer wait (Inform WDT controller)
@ normal
Normal operation Task controller.
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)
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.
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.
uint8_t running_pos
!=0 (CREATE) Task Started (Generic state of Task)
task_flag state
Long sleep Task.
wdt_flag watch_dog
WatchDog of Task.
uint16_t stack
Stack Max Usage Monitor.
uint8_t running_sub
Optional SubState of Task.