Path: blob/master/libraries/AP_CSVReader/AP_CSVReader.h
9539 views
#pragma once12// Note: term is always null-terminated so a final line with no cr/lf3// on it can still be fetched by the caller45#include <stdint.h>67class AP_CSVReader8{910public:1112AP_CSVReader(uint8_t *_term, uint8_t _term_len, uint8_t _separator=',') :13separator{_separator},14term{_term},15term_len{_term_len}16{}1718enum class RetCode : uint8_t {19OK,20ERROR,21TERM_DONE,22VECTOR_DONE,23};2425RetCode feed(uint8_t c);26// RetCode feed(const uint8_t *buffer, uint8_t len);2728private:2930enum class State : uint8_t {31START_OF_START_OF_TERM = 46,32START_OF_TERM = 47,33END_OF_VECTOR_CR = 48,34IN_UNQUOTED_TERM = 49,35IN_QUOTED_TERM = 50,36END_OF_QUOTED_TERM = 51,37} state = State::START_OF_START_OF_TERM;3839// term separator40const uint8_t separator;4142// pointer to memory where term will be assembled43uint8_t *term;4445// amount of memory term points to46const uint8_t term_len;4748// offset into term for next character49uint8_t term_ofs;5051void set_state(State newstate) {52state = newstate;53}5455AP_CSVReader::RetCode handle_unquoted_term(uint8_t c);56AP_CSVReader::RetCode handle_quoted_term(uint8_t c);57};585960