Skip to content

Commit b22d060

Browse files
authored
checkDataFormat() and unit test updates (#54)
* Binaryデータ出力時は実機とテストの両方で動作確認完了、ASCIIデータには未対応、デバッグ用出力あり * 実機とテストの両方でBinaryとASCIIの判定に成功、BinaryでもASCIIでもないデータには未対応 * タイムアウト機能を追加&hasCompletedFormatCheck()と関係する変数を削除 * 不正なデータをチェックするようにテストを修正 * readを成功させるためにwhileループにsleep処理を追加 * 必要がなかったため、while文のsleep処理を削除 * テスト用データの作成で重複している箇所を関数化 * RCLCPP_INFOをWARNに変更&不要なコメントを削除 * const autoをできる限り使用 * actions/checkoutのバージョンを3から4に更新 * 読み取ったデータをある程度貯めてからデータ形式を判定するように変更 * 貯めるデータを更新するように修正 * メンバ変数の名前を修正&256を定数化
1 parent faf39b0 commit b22d060

File tree

6 files changed

+180
-92
lines changed

6 files changed

+180
-92
lines changed

.github/workflows/industrial_ci.yml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,6 @@ jobs:
1919

2020
runs-on: ubuntu-latest
2121
steps:
22-
- uses: actions/checkout@v3
22+
- uses: actions/checkout@v4
2323
- uses: "ros-industrial/industrial_ci@master"
2424
env: ${{ matrix.env }}

include/rt_usb_9axisimu_driver/rt_usb_9axisimu.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -106,6 +106,8 @@ class Consts
106106
IMU_ASCII_DATA_SIZE
107107
};
108108

109+
static constexpr int READ_BUFFER_SIZE = 256;
110+
109111
// Convertor
110112
const double CONVERTOR_RAW2G;
111113
const double CONVERTOR_RAW2DPS;

include/rt_usb_9axisimu_driver/rt_usb_9axisimu_driver.hpp

Lines changed: 8 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -57,6 +57,11 @@ class RtUsb9axisimuRosDriver
5757
double magnetic_field_stddev_;
5858
rt_usb_9axisimu::Consts consts;
5959

60+
unsigned char bin_read_buffer_[rt_usb_9axisimu::Consts::READ_BUFFER_SIZE];
61+
unsigned char ascii_read_buffer_[rt_usb_9axisimu::Consts::READ_BUFFER_SIZE];
62+
unsigned int bin_read_buffer_idx_ = 0;
63+
unsigned int ascii_read_buffer_idx_ = 0;
64+
6065
enum DataFormat
6166
{
6267
NONE = 0,
@@ -66,16 +71,16 @@ class RtUsb9axisimuRosDriver
6671
ASCII,
6772
INCORRECT
6873
};
69-
bool has_completed_format_check_;
7074
DataFormat data_format_;
7175
bool has_refreshed_imu_data_;
7276

7377
// Method to combine two separate one-byte data into one two-byte data
7478
int16_t combineByteData(unsigned char data_h, unsigned char data_l);
7579
// Method to extract binary sensor data from communication buffer
7680
rt_usb_9axisimu::ImuData<int16_t> extractBinarySensorData(unsigned char * imu_data_buf);
77-
bool isBinarySensorData(unsigned char * imu_data_buf);
81+
bool isBinarySensorData(unsigned char * imu_data_buf, unsigned int data_size);
7882
bool readBinaryData(void);
83+
bool isAsciiSensorData(unsigned char * imu_data_buf, unsigned int data_size);
7984
bool isValidAsciiSensorData(std::vector<std::string> imu_data_vector_buf);
8085
bool readAsciiData(void);
8186

@@ -90,8 +95,7 @@ class RtUsb9axisimuRosDriver
9095

9196
bool startCommunication();
9297
void stopCommunication(void);
93-
void checkDataFormat(void);
94-
bool hasCompletedFormatCheck(void);
98+
void checkDataFormat(const double timeout = 5.0);
9599
bool hasAsciiDataFormat(void);
96100
bool hasBinaryDataFormat(void);
97101
bool hasRefreshedImuData(void);

src/rt_usb_9axisimu_driver.cpp

Lines changed: 86 additions & 30 deletions
Original file line numberDiff line numberDiff line change
@@ -31,11 +31,10 @@
3131
* POSSIBILITY OF SUCH DAMAGE.
3232
*/
3333

34-
#include <cstring>
3534
#include <memory>
36-
#include <string>
3735
#include <utility>
3836
#include <vector>
37+
#include <chrono>
3938

4039
#include "rt_usb_9axisimu_driver/rt_usb_9axisimu_driver.hpp"
4140

@@ -83,10 +82,28 @@ RtUsb9axisimuRosDriver::extractBinarySensorData(unsigned char * imu_data_buf)
8382
return imu_rawdata;
8483
}
8584

86-
bool RtUsb9axisimuRosDriver::isBinarySensorData(unsigned char * imu_data_buf)
85+
bool RtUsb9axisimuRosDriver::isBinarySensorData(unsigned char * imu_data_buf, unsigned int data_size)
8786
{
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)
90107
{
91108
return true;
92109
}
@@ -96,7 +113,7 @@ bool RtUsb9axisimuRosDriver::isBinarySensorData(unsigned char * imu_data_buf)
96113
bool RtUsb9axisimuRosDriver::readBinaryData(void)
97114
{
98115
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];
100117

101118
has_refreshed_imu_data_ = false;
102119
int read_data_size = serial_port_->readFromDevice(read_data_buf,
@@ -122,7 +139,7 @@ bool RtUsb9axisimuRosDriver::readBinaryData(void)
122139
return true;
123140
}
124141

125-
if (isBinarySensorData(imu_binary_data_buffer.data()) == false) {
142+
if (isBinarySensorData(imu_binary_data_buffer.data(), imu_binary_data_buffer.size()) == false) {
126143
imu_binary_data_buffer.clear();
127144
return false;
128145
}
@@ -137,6 +154,44 @@ bool RtUsb9axisimuRosDriver::readBinaryData(void)
137154
return true;
138155
}
139156

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+
140195
bool RtUsb9axisimuRosDriver::isValidAsciiSensorData(std::vector<std::string> str_vector)
141196
{
142197
for (int i = 1; i < consts.IMU_ASCII_DATA_SIZE; i++) {
@@ -151,7 +206,7 @@ bool RtUsb9axisimuRosDriver::readAsciiData(void)
151206
{
152207
static std::vector<std::string> imu_data_vector_buf;
153208

154-
unsigned char imu_data_buf[256];
209+
unsigned char imu_data_buf[consts.READ_BUFFER_SIZE];
155210
rt_usb_9axisimu::ImuData<double> imu_data;
156211
std::string imu_data_oneline_buf;
157212

@@ -207,15 +262,13 @@ bool RtUsb9axisimuRosDriver::readAsciiData(void)
207262
RtUsb9axisimuRosDriver::RtUsb9axisimuRosDriver(std::string port = "")
208263
{
209264
serial_port_ = std::make_unique<rt_usb_9axisimu::SerialPort>(port.c_str());
210-
has_completed_format_check_ = false;
211265
data_format_ = DataFormat::NONE;
212266
has_refreshed_imu_data_ = false;
213267
}
214268

215269
RtUsb9axisimuRosDriver::RtUsb9axisimuRosDriver(std::unique_ptr<rt_usb_9axisimu::SerialPort> serial_port)
216270
{
217271
serial_port_ = std::move(serial_port);
218-
has_completed_format_check_ = false;
219272
data_format_ = DataFormat::NONE;
220273
has_refreshed_imu_data_ = false;
221274
}
@@ -252,33 +305,36 @@ bool RtUsb9axisimuRosDriver::startCommunication()
252305
void RtUsb9axisimuRosDriver::stopCommunication(void)
253306
{
254307
serial_port_->closeSerialPort();
255-
has_completed_format_check_ = false;
256308
data_format_ = DataFormat::NONE;
257309
has_refreshed_imu_data_ = false;
258310
}
259311

260-
void RtUsb9axisimuRosDriver::checkDataFormat(void)
312+
void RtUsb9axisimuRosDriver::checkDataFormat(const double timeout)
261313
{
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;
272320
}
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));
278324

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+
}
282338
}
283339

284340
bool RtUsb9axisimuRosDriver::hasAsciiDataFormat(void)

src/rt_usb_9axisimu_driver_component.cpp

Lines changed: 9 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -93,21 +93,16 @@ CallbackReturn Driver::on_configure(const rclcpp_lifecycle::State &)
9393
return CallbackReturn::FAILURE;
9494
}
9595

96-
while (rclcpp::ok() && driver_->hasCompletedFormatCheck() == false) {
97-
driver_->checkDataFormat();
98-
}
96+
driver_->checkDataFormat();
9997

100-
if (rclcpp::ok() && driver_->hasCompletedFormatCheck()) {
101-
RCLCPP_INFO(this->get_logger(), "Format check has completed.");
102-
if (driver_->hasAsciiDataFormat()) {
103-
RCLCPP_INFO(this->get_logger(), "Data format is ascii.");
104-
} else if (driver_->hasBinaryDataFormat()) {
105-
RCLCPP_INFO(this->get_logger(), "Data format is binary.");
106-
} else {
107-
RCLCPP_INFO(this->get_logger(), "Data format is neither binary nor ascii.");
108-
driver_->stopCommunication();
109-
return CallbackReturn::FAILURE;
110-
}
98+
if (driver_->hasAsciiDataFormat()) {
99+
RCLCPP_INFO(this->get_logger(), "Data format is ascii.");
100+
} else if (driver_->hasBinaryDataFormat()) {
101+
RCLCPP_INFO(this->get_logger(), "Data format is binary.");
102+
} else {
103+
RCLCPP_WARN(this->get_logger(), "Data format is neither binary nor ascii.");
104+
driver_->stopCommunication();
105+
return CallbackReturn::FAILURE;
111106
}
112107

113108
imu_data_raw_pub_ = create_publisher<sensor_msgs::msg::Imu>("imu/data_raw", 1);

0 commit comments

Comments
 (0)
pFad - Phonifier reborn

Pfad - The Proxy pFad of © 2024 Garber Painting. All rights reserved.

Note: This service is not intended for secure transactions such as banking, social media, email, or purchasing. Use at your own risk. We assume no liability whatsoever for broken pages.


Alternative Proxies:

Alternative Proxy

pFad Proxy

pFad v3 Proxy

pFad v4 Proxy