31
31
* POSSIBILITY OF SUCH DAMAGE.
32
32
*/
33
33
34
- #include < cstring>
35
34
#include < memory>
36
- #include < string>
37
35
#include < utility>
38
36
#include < vector>
37
+ #include < chrono>
39
38
40
39
#include " rt_usb_9axisimu_driver/rt_usb_9axisimu_driver.hpp"
41
40
@@ -83,10 +82,28 @@ RtUsb9axisimuRosDriver::extractBinarySensorData(unsigned char * imu_data_buf)
83
82
return imu_rawdata;
84
83
}
85
84
86
- bool RtUsb9axisimuRosDriver::isBinarySensorData (unsigned char * imu_data_buf)
85
+ bool RtUsb9axisimuRosDriver::isBinarySensorData (unsigned char * imu_data_buf, unsigned int data_size )
87
86
{
88
- if (imu_data_buf[consts.IMU_BIN_HEADER_R ] == ' R' &&
89
- imu_data_buf[consts.IMU_BIN_HEADER_T ] == ' T' )
87
+ for (int i = 0 ; i < (int )data_size; i++) {
88
+ bin_read_buffer_[bin_read_buffer_idx_] = imu_data_buf[i];
89
+ bin_read_buffer_idx_++;
90
+ if (bin_read_buffer_idx_ >= consts.READ_BUFFER_SIZE ) bin_read_buffer_idx_ = 0 ;
91
+ }
92
+
93
+ int start_idx = 0 ;
94
+ for (int i = 0 ; i < (int )(bin_read_buffer_idx_ - consts.IMU_BIN_DATA_SIZE ); i++) {
95
+ if (imu_data_buf[i] == 0xff ) {
96
+ start_idx = i;
97
+ break ;
98
+ }
99
+ }
100
+
101
+ if (imu_data_buf[start_idx + consts.IMU_BIN_HEADER_FF0 ] == 0xff &&
102
+ imu_data_buf[start_idx + consts.IMU_BIN_HEADER_FF1 ] == 0xff &&
103
+ imu_data_buf[start_idx + consts.IMU_BIN_HEADER_R ] == ' R' &&
104
+ imu_data_buf[start_idx + consts.IMU_BIN_HEADER_T ] == ' T' &&
105
+ imu_data_buf[start_idx + consts.IMU_BIN_HEADER_ID0 ] == 0x39 &&
106
+ imu_data_buf[start_idx + consts.IMU_BIN_HEADER_ID1 ] == 0x41 )
90
107
{
91
108
return true ;
92
109
}
@@ -96,7 +113,7 @@ bool RtUsb9axisimuRosDriver::isBinarySensorData(unsigned char * imu_data_buf)
96
113
bool RtUsb9axisimuRosDriver::readBinaryData (void )
97
114
{
98
115
static std::vector<unsigned char > imu_binary_data_buffer;
99
- unsigned char read_data_buf[256 ];
116
+ unsigned char read_data_buf[consts. READ_BUFFER_SIZE ];
100
117
101
118
has_refreshed_imu_data_ = false ;
102
119
int read_data_size = serial_port_->readFromDevice (read_data_buf,
@@ -122,7 +139,7 @@ bool RtUsb9axisimuRosDriver::readBinaryData(void)
122
139
return true ;
123
140
}
124
141
125
- if (isBinarySensorData (imu_binary_data_buffer.data ()) == false ) {
142
+ if (isBinarySensorData (imu_binary_data_buffer.data (), imu_binary_data_buffer. size () ) == false ) {
126
143
imu_binary_data_buffer.clear ();
127
144
return false ;
128
145
}
@@ -137,6 +154,44 @@ bool RtUsb9axisimuRosDriver::readBinaryData(void)
137
154
return true ;
138
155
}
139
156
157
+ bool RtUsb9axisimuRosDriver::isAsciiSensorData (unsigned char * imu_data_buf, unsigned int data_size)
158
+ {
159
+ for (int i = 0 ; i < (int )data_size; i++) {
160
+ ascii_read_buffer_[ascii_read_buffer_idx_] = imu_data_buf[i];
161
+ ascii_read_buffer_idx_++;
162
+ if (ascii_read_buffer_idx_ >= consts.READ_BUFFER_SIZE ) ascii_read_buffer_idx_ = 0 ;
163
+ }
164
+
165
+ // convert imu data to vector in ascii format
166
+ std::vector<std::vector<std::string>> data_vector_ascii;
167
+ std::vector<std::string> data_oneset_ascii;
168
+ std::string data_oneline_ascii;
169
+ for (int char_count = 0 ; char_count < (int )ascii_read_buffer_idx_; char_count++) {
170
+ if (ascii_read_buffer_[char_count] == ' \n ' ) {
171
+ data_oneset_ascii.push_back (data_oneline_ascii);
172
+ data_vector_ascii.push_back (data_oneset_ascii);
173
+ data_oneline_ascii.clear ();
174
+ data_oneset_ascii.clear ();
175
+ }
176
+ else if (ascii_read_buffer_[char_count] == ' ,' ) {
177
+ data_oneset_ascii.push_back (data_oneline_ascii);
178
+ data_oneline_ascii.clear ();
179
+ } else {
180
+ data_oneline_ascii += ascii_read_buffer_[char_count];
181
+ }
182
+ }
183
+
184
+ // check data is in ascii format
185
+ for (int i = 0 ; i < (int )data_vector_ascii.size (); i++) {
186
+ if (data_vector_ascii.at (i).size () == consts.IMU_ASCII_DATA_SIZE &&
187
+ data_vector_ascii.at (i).at (consts.IMU_ASCII_TIMESTAMP ).find (" ." ) == std::string::npos &&
188
+ isValidAsciiSensorData (data_vector_ascii.at (i))) {
189
+ return true ;
190
+ }
191
+ }
192
+ return false ;
193
+ }
194
+
140
195
bool RtUsb9axisimuRosDriver::isValidAsciiSensorData (std::vector<std::string> str_vector)
141
196
{
142
197
for (int i = 1 ; i < consts.IMU_ASCII_DATA_SIZE ; i++) {
@@ -151,7 +206,7 @@ bool RtUsb9axisimuRosDriver::readAsciiData(void)
151
206
{
152
207
static std::vector<std::string> imu_data_vector_buf;
153
208
154
- unsigned char imu_data_buf[256 ];
209
+ unsigned char imu_data_buf[consts. READ_BUFFER_SIZE ];
155
210
rt_usb_9axisimu::ImuData<double > imu_data;
156
211
std::string imu_data_oneline_buf;
157
212
@@ -207,15 +262,13 @@ bool RtUsb9axisimuRosDriver::readAsciiData(void)
207
262
RtUsb9axisimuRosDriver::RtUsb9axisimuRosDriver (std::string port = " " )
208
263
{
209
264
serial_port_ = std::make_unique<rt_usb_9axisimu::SerialPort>(port.c_str ());
210
- has_completed_format_check_ = false ;
211
265
data_format_ = DataFormat::NONE;
212
266
has_refreshed_imu_data_ = false ;
213
267
}
214
268
215
269
RtUsb9axisimuRosDriver::RtUsb9axisimuRosDriver (std::unique_ptr<rt_usb_9axisimu::SerialPort> serial_port)
216
270
{
217
271
serial_port_ = std::move (serial_port);
218
- has_completed_format_check_ = false ;
219
272
data_format_ = DataFormat::NONE;
220
273
has_refreshed_imu_data_ = false ;
221
274
}
@@ -252,33 +305,36 @@ bool RtUsb9axisimuRosDriver::startCommunication()
252
305
void RtUsb9axisimuRosDriver::stopCommunication (void )
253
306
{
254
307
serial_port_->closeSerialPort ();
255
- has_completed_format_check_ = false ;
256
308
data_format_ = DataFormat::NONE;
257
309
has_refreshed_imu_data_ = false ;
258
310
}
259
311
260
- void RtUsb9axisimuRosDriver::checkDataFormat (void )
312
+ void RtUsb9axisimuRosDriver::checkDataFormat (const double timeout )
261
313
{
262
- if (data_format_ == DataFormat::NONE) {
263
- unsigned char data_buf[256 ];
264
- int data_size_of_buf = serial_port_->readFromDevice (data_buf, consts.IMU_BIN_DATA_SIZE );
265
- if (data_size_of_buf == consts.IMU_BIN_DATA_SIZE ) {
266
- if (isBinarySensorData (data_buf)) {
267
- data_format_ = DataFormat::BINARY;
268
- has_completed_format_check_ = true ;
269
- } else {
270
- data_format_ = DataFormat::NOT_BINARY;
271
- }
314
+ const auto start_time = std::chrono::system_clock::now ();
315
+ while (data_format_ == DataFormat::NONE) {
316
+ const auto end_time = std::chrono::system_clock::now ();
317
+ const double time_elapsed = (double )std::chrono::duration_cast<std::chrono::seconds>(end_time - start_time).count ();
318
+ if (time_elapsed > timeout) {
319
+ return ;
272
320
}
273
- } else if (data_format_ == DataFormat::NOT_BINARY) {
274
- data_format_ = DataFormat::ASCII;
275
- has_completed_format_check_ = true ;
276
- }
277
- }
321
+
322
+ unsigned char read_buffer[consts.READ_BUFFER_SIZE ];
323
+ const auto read_size = serial_port_->readFromDevice (read_buffer, sizeof (read_buffer));
278
324
279
- bool RtUsb9axisimuRosDriver::hasCompletedFormatCheck (void )
280
- {
281
- return has_completed_format_check_;
325
+ if (read_size <= 0 ) {
326
+ continue ;
327
+ }
328
+
329
+ if (isBinarySensorData (read_buffer, read_size)) {
330
+ data_format_ = DataFormat::BINARY;
331
+ return ;
332
+ }
333
+ else if (isAsciiSensorData (read_buffer, read_size)) {
334
+ data_format_ = DataFormat::ASCII;
335
+ return ;
336
+ }
337
+ }
282
338
}
283
339
284
340
bool RtUsb9axisimuRosDriver::hasAsciiDataFormat (void )
0 commit comments