CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_CSVReader/AP_CSVReader.cpp
Views: 1798
1
#include "AP_CSVReader.h"
2
3
#include <AP_Common/AP_Common.h>
4
5
#include <stdio.h>
6
7
AP_CSVReader::RetCode AP_CSVReader::handle_unquoted_term(uint8_t c)
8
{
9
if (c == separator) {
10
set_state(State::START_OF_START_OF_TERM);
11
return RetCode::TERM_DONE;
12
}
13
switch (c) {
14
case '\r':
15
set_state(State::END_OF_VECTOR_CR);
16
return RetCode::VECTOR_DONE;
17
case '\n':
18
set_state(State::START_OF_START_OF_TERM);
19
return RetCode::VECTOR_DONE;
20
default:
21
if (term_ofs >= term_len-1) { // -1 for null termination
22
return RetCode::ERROR;
23
}
24
term[term_ofs++] = c;
25
term[term_ofs] = '\0';
26
return RetCode::OK;
27
}
28
}
29
30
AP_CSVReader::RetCode AP_CSVReader::handle_quoted_term(uint8_t c)
31
{
32
if (c == '"') {
33
set_state(State::END_OF_QUOTED_TERM);
34
return RetCode::OK;
35
}
36
if (state == State::END_OF_QUOTED_TERM) {
37
if (c == separator) {
38
set_state(State::START_OF_START_OF_TERM);
39
return RetCode::TERM_DONE;
40
}
41
42
switch (c) {
43
case '\r':
44
set_state(State::END_OF_VECTOR_CR);
45
return RetCode::VECTOR_DONE;
46
case '\n':
47
set_state(State::START_OF_START_OF_TERM);
48
return RetCode::VECTOR_DONE;
49
}
50
return RetCode::ERROR;
51
}
52
53
// still within the quoted term, append to current value
54
if (term_ofs >= term_len-1) { // -1 for null termination
55
return RetCode::ERROR;
56
}
57
term[term_ofs++] = c;
58
term[term_ofs] = '\0';
59
return RetCode::OK;
60
}
61
62
AP_CSVReader::RetCode AP_CSVReader::feed(uint8_t c)
63
{
64
if (term_len == 0) {
65
return RetCode::ERROR;
66
}
67
68
again:
69
switch (state) {
70
case State::START_OF_START_OF_TERM:
71
term_ofs = 0;
72
term[term_ofs] = '\0';
73
state = State::START_OF_TERM;
74
FALLTHROUGH;
75
case State::START_OF_TERM:
76
// if (c == '"') {
77
// set_state(State::START_OF_QUOTED_TERM);
78
// return RetCode::OK;
79
// }
80
if (c == '"') {
81
set_state(State::IN_QUOTED_TERM);
82
return RetCode::OK;
83
} else {
84
set_state(State::IN_UNQUOTED_TERM);
85
return handle_unquoted_term(c);
86
}
87
case State::END_OF_VECTOR_CR:
88
if (c == '\n') {
89
set_state(State::START_OF_START_OF_TERM);
90
return RetCode::OK;
91
}
92
set_state(State::START_OF_START_OF_TERM);
93
goto again;
94
case State::IN_UNQUOTED_TERM:
95
return handle_unquoted_term(c);
96
case State::IN_QUOTED_TERM:
97
case State::END_OF_QUOTED_TERM:
98
return handle_quoted_term(c);
99
}
100
101
return RetCode::ERROR;
102
}
103
104