19 #ifndef XSENS_DRIVER__XSENS_BASE_TRANSLATOR_HPP_
20 #define XSENS_DRIVER__XSENS_BASE_TRANSLATOR_HPP_
40 namespace xsens_driver
43 template<
typename Derived,
typename MessageT>
73 : current_state_(
State::START) {}
77 if ((data_id & 0x0003) == 0x3) {
79 }
else if ((data_id & 0x0003) == 0x0) {
82 throw std::runtime_error(
"fixed point precision not supported.");
96 switch (current_state_) {
98 if (pkt.data == 0xFA) {
99 current_state_ = State::PREAMBLE_READ;
101 current_state_ = State::START;
104 case State::PREAMBLE_READ:
105 if (pkt.data == 0xFF) {
106 current_state_ = State::BID_READ;
108 current_state_ = State::START;
111 case State::BID_READ:
113 current_state_ = State::MID_READ;
115 case State::MID_READ:
116 current_length_ = pkt.data;
117 current_state_ = State::LENGTH_READ;
119 case State::LENGTH_READ:
120 if (raw_message_.size() == current_length_) {
121 std::size_t checksum = 0xFF;
124 using MID_underlying_type = std::underlying_type_t<decltype(current_mid_)>;
125 checksum +=
static_cast<MID_underlying_type
>(current_mid_);
126 checksum += current_length_;
127 checksum += pkt.data;
129 std::accumulate(std::begin(raw_message_),
std::end(raw_message_), checksum);
132 current_state_ = State::START;
134 raw_message_.clear();
139 throw std::runtime_error(
"Legacy data not supported yet");
143 current_state_ = State::START;
145 raw_message_.clear();
149 raw_message_.push_back(pkt.data);
159 auto data = raw_message_;
162 while (!data.empty()) {
163 const int32_t data_id = data[1] | data[0] << 8;
164 const int32_t message_size = data[2];
168 auto content = decltype(data)(
169 std::begin(data) + 3,
170 std::begin(data) + 3 + message_size);
173 data = decltype(data)(
174 std::begin(data) + 3 + message_size,
177 int32_t group = data_id & 0xF800;
180 this->impl().parse_xdigroup_mtdata2(xdigroup,
output, data_id, content);
189 #endif // XSENS_DRIVER__XSENS_BASE_TRANSLATOR_HPP_