Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

checkDataFormat() and unit test updates #54

Merged
merged 13 commits into from
Aug 6, 2024
Merged
Show file tree
Hide file tree
Changes from 6 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 2 additions & 3 deletions include/rt_usb_9axisimu_driver/rt_usb_9axisimu_driver.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,6 @@ class RtUsb9axisimuRosDriver
ASCII,
INCORRECT
};
bool has_completed_format_check_;
DataFormat data_format_;
bool has_refreshed_imu_data_;

Expand All @@ -76,6 +75,7 @@ class RtUsb9axisimuRosDriver
rt_usb_9axisimu::ImuData<int16_t> extractBinarySensorData(unsigned char * imu_data_buf);
bool isBinarySensorData(unsigned char * imu_data_buf);
bool readBinaryData(void);
bool isAsciiSensorData(unsigned char * imu_data_buf, int data_size);
bool isValidAsciiSensorData(std::vector<std::string> imu_data_vector_buf);
bool readAsciiData(void);

Expand All @@ -90,8 +90,7 @@ class RtUsb9axisimuRosDriver

bool startCommunication();
void stopCommunication(void);
void checkDataFormat(void);
bool hasCompletedFormatCheck(void);
void checkDataFormat(const double timeout = 5.0);
bool hasAsciiDataFormat(void);
bool hasBinaryDataFormat(void);
bool hasRefreshedImuData(void);
Expand Down
84 changes: 58 additions & 26 deletions src/rt_usb_9axisimu_driver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,11 +31,10 @@
* POSSIBILITY OF SUCH DAMAGE.
*/

#include <cstring>
#include <memory>
#include <string>
#include <utility>
#include <vector>
#include <chrono>

#include "rt_usb_9axisimu_driver/rt_usb_9axisimu_driver.hpp"

Expand Down Expand Up @@ -85,8 +84,12 @@ RtUsb9axisimuRosDriver::extractBinarySensorData(unsigned char * imu_data_buf)

bool RtUsb9axisimuRosDriver::isBinarySensorData(unsigned char * imu_data_buf)
{
if (imu_data_buf[consts.IMU_BIN_HEADER_R] == 'R' &&
imu_data_buf[consts.IMU_BIN_HEADER_T] == 'T')
if (imu_data_buf[consts.IMU_BIN_HEADER_FF0] == 0xff &&
imu_data_buf[consts.IMU_BIN_HEADER_FF1] == 0xff &&
imu_data_buf[consts.IMU_BIN_HEADER_R] == 'R' &&
imu_data_buf[consts.IMU_BIN_HEADER_T] == 'T' &&
imu_data_buf[consts.IMU_BIN_HEADER_ID0] == 0x39 &&
imu_data_buf[consts.IMU_BIN_HEADER_ID1] == 0x41)
{
return true;
}
Expand Down Expand Up @@ -137,6 +140,32 @@ bool RtUsb9axisimuRosDriver::readBinaryData(void)
return true;
}

bool RtUsb9axisimuRosDriver::isAsciiSensorData(unsigned char * imu_data_buf, int data_size)
{
// convert imu data to vector in ascii format
std::vector<std::string> data_vector_ascii;
std::string data_oneline_ascii;
for (int char_count = 0; char_count < data_size; char_count++) {
if (imu_data_buf[char_count] == ',' || imu_data_buf[char_count] == '\n') {
data_vector_ascii.push_back(data_oneline_ascii);
data_oneline_ascii.clear();
} else {
data_oneline_ascii += imu_data_buf[char_count];
}
if (imu_data_buf[char_count] == '\n') {
break;
}
}

// check data is in ascii format
if (data_vector_ascii.size() == consts.IMU_ASCII_DATA_SIZE &&
data_vector_ascii[consts.IMU_ASCII_TIMESTAMP].find(".") == std::string::npos &&
isValidAsciiSensorData(data_vector_ascii)) {
return true;
}
return false;
}

bool RtUsb9axisimuRosDriver::isValidAsciiSensorData(std::vector<std::string> str_vector)
{
for (int i = 1; i < consts.IMU_ASCII_DATA_SIZE; i++) {
Expand Down Expand Up @@ -207,15 +236,13 @@ bool RtUsb9axisimuRosDriver::readAsciiData(void)
RtUsb9axisimuRosDriver::RtUsb9axisimuRosDriver(std::string port = "")
{
serial_port_ = std::make_unique<rt_usb_9axisimu::SerialPort>(port.c_str());
has_completed_format_check_ = false;
data_format_ = DataFormat::NONE;
has_refreshed_imu_data_ = false;
}

RtUsb9axisimuRosDriver::RtUsb9axisimuRosDriver(std::unique_ptr<rt_usb_9axisimu::SerialPort> serial_port)
{
serial_port_ = std::move(serial_port);
has_completed_format_check_ = false;
data_format_ = DataFormat::NONE;
has_refreshed_imu_data_ = false;
}
Expand Down Expand Up @@ -252,33 +279,38 @@ bool RtUsb9axisimuRosDriver::startCommunication()
void RtUsb9axisimuRosDriver::stopCommunication(void)
{
serial_port_->closeSerialPort();
has_completed_format_check_ = false;
data_format_ = DataFormat::NONE;
has_refreshed_imu_data_ = false;
}

void RtUsb9axisimuRosDriver::checkDataFormat(void)
void RtUsb9axisimuRosDriver::checkDataFormat(const double timeout)
{
if (data_format_ == DataFormat::NONE) {
unsigned char data_buf[256];
int data_size_of_buf = serial_port_->readFromDevice(data_buf, consts.IMU_BIN_DATA_SIZE);
if (data_size_of_buf == consts.IMU_BIN_DATA_SIZE) {
if (isBinarySensorData(data_buf)) {
data_format_ = DataFormat::BINARY;
has_completed_format_check_ = true;
} else {
data_format_ = DataFormat::NOT_BINARY;
}
auto start_time = std::chrono::system_clock::now();
while (data_format_ == DataFormat::NONE) {
// time out (default 5.0s)
ShotaAk marked this conversation as resolved.
Show resolved Hide resolved
// Measures for data formats that are neither Binary nor ASCII
ShotaAk marked this conversation as resolved.
Show resolved Hide resolved
auto end_time = std::chrono::system_clock::now();
double time_elapsed = (double)std::chrono::duration_cast<std::chrono::seconds>(end_time - start_time).count();
ShotaAk marked this conversation as resolved.
Show resolved Hide resolved
if (time_elapsed > timeout) {
return;
}
} else if (data_format_ == DataFormat::NOT_BINARY) {
data_format_ = DataFormat::ASCII;
has_completed_format_check_ = true;
}
}

unsigned char read_buffer[256];
int read_size = serial_port_->readFromDevice(read_buffer, sizeof(read_buffer));
ShotaAk marked this conversation as resolved.
Show resolved Hide resolved

bool RtUsb9axisimuRosDriver::hasCompletedFormatCheck(void)
{
return has_completed_format_check_;
if(read_size <= 0) {
continue;
}

if (isBinarySensorData(read_buffer)) {
data_format_ = DataFormat::BINARY;
return;
}
else if (isAsciiSensorData(read_buffer, read_size)) {
data_format_ = DataFormat::ASCII;
return;
}
}
}

bool RtUsb9axisimuRosDriver::hasAsciiDataFormat(void)
Expand Down
23 changes: 9 additions & 14 deletions src/rt_usb_9axisimu_driver_component.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -93,21 +93,16 @@ CallbackReturn Driver::on_configure(const rclcpp_lifecycle::State &)
return CallbackReturn::FAILURE;
}

while (rclcpp::ok() && driver_->hasCompletedFormatCheck() == false) {
driver_->checkDataFormat();
}
driver_->checkDataFormat();

if (rclcpp::ok() && driver_->hasCompletedFormatCheck()) {
RCLCPP_INFO(this->get_logger(), "Format check has completed.");
if (driver_->hasAsciiDataFormat()) {
RCLCPP_INFO(this->get_logger(), "Data format is ascii.");
} else if (driver_->hasBinaryDataFormat()) {
RCLCPP_INFO(this->get_logger(), "Data format is binary.");
} else {
RCLCPP_INFO(this->get_logger(), "Data format is neither binary nor ascii.");
driver_->stopCommunication();
return CallbackReturn::FAILURE;
}
if (driver_->hasAsciiDataFormat()) {
RCLCPP_INFO(this->get_logger(), "Data format is ascii.");
} else if (driver_->hasBinaryDataFormat()) {
RCLCPP_INFO(this->get_logger(), "Data format is binary.");
} else {
RCLCPP_INFO(this->get_logger(), "Data format is neither binary nor ascii.");
ShotaAk marked this conversation as resolved.
Show resolved Hide resolved
driver_->stopCommunication();
return CallbackReturn::FAILURE;
}

imu_data_raw_pub_ = create_publisher<sensor_msgs::msg::Imu>("imu/data_raw", 1);
Expand Down
89 changes: 69 additions & 20 deletions test/test_driver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,8 +31,7 @@
* POSSIBILITY OF SUCH DAMAGE.
*/

#include <array>
#include <string>
#include <vector>
#include <gtest/gtest.h>
#include "fakeit.hpp"
#include "rt_usb_9axisimu_driver/rt_usb_9axisimu_driver.hpp"
Expand Down Expand Up @@ -74,7 +73,6 @@ TEST(TestDriver, initialize_member_variables)
RtUsb9axisimuRosDriver driver(
std::unique_ptr<SerialPort>(&mock.get()));

EXPECT_FALSE(driver.hasCompletedFormatCheck());
EXPECT_FALSE(driver.hasBinaryDataFormat());
EXPECT_FALSE(driver.hasAsciiDataFormat());
EXPECT_FALSE(driver.hasRefreshedImuData());
Expand All @@ -85,12 +83,33 @@ TEST(TestDriver, checkDataFormat_Binary)
// Expect to check correctly when read data in binary format
auto mock = create_serial_port_mock();

// 1st: invalid binary data ('R' and 'T' positions are reversed)
// 2nd: correct binary data ('R' and 'T' are in the correct position)
When(Method(mock, readFromDevice)).Do([](
unsigned char* buf, unsigned int buf_size) {
rt_usb_9axisimu::Consts consts;
unsigned char dummy_bin_imu_data[consts.IMU_BIN_DATA_SIZE] = {0};
dummy_bin_imu_data[consts.IMU_BIN_HEADER_FF0] = 0xff;
dummy_bin_imu_data[consts.IMU_BIN_HEADER_FF1] = 0xff;
dummy_bin_imu_data[consts.IMU_BIN_HEADER_R] = 0x54; // T
dummy_bin_imu_data[consts.IMU_BIN_HEADER_T] = 0x52; // R
dummy_bin_imu_data[consts.IMU_BIN_HEADER_ID0] = 0x39;
dummy_bin_imu_data[consts.IMU_BIN_HEADER_ID1] = 0x41;
for(int i = 0; i < consts.IMU_BIN_DATA_SIZE; i++) {
buf[i] = dummy_bin_imu_data[i];
}
buf_size = consts.IMU_BIN_DATA_SIZE;
return buf_size;
}).Do([](
unsigned char* buf, unsigned int buf_size) {
rt_usb_9axisimu::Consts consts;
unsigned char dummy_bin_imu_data[consts.IMU_BIN_DATA_SIZE] = {0};
dummy_bin_imu_data[consts.IMU_BIN_HEADER_FF0] = 0xff;
dummy_bin_imu_data[consts.IMU_BIN_HEADER_FF1] = 0xff;
dummy_bin_imu_data[consts.IMU_BIN_HEADER_R] = 0x52; // R
dummy_bin_imu_data[consts.IMU_BIN_HEADER_T] = 0x54; // T
dummy_bin_imu_data[consts.IMU_BIN_HEADER_ID0] = 0x39;
dummy_bin_imu_data[consts.IMU_BIN_HEADER_ID1] = 0x41;
YusukeKato marked this conversation as resolved.
Show resolved Hide resolved
for(int i = 0; i < consts.IMU_BIN_DATA_SIZE; i++) {
buf[i] = dummy_bin_imu_data[i];
}
Expand All @@ -103,7 +122,6 @@ TEST(TestDriver, checkDataFormat_Binary)

driver.checkDataFormat();

EXPECT_TRUE(driver.hasCompletedFormatCheck());
EXPECT_TRUE(driver.hasBinaryDataFormat());
EXPECT_FALSE(driver.hasAsciiDataFormat());
}
Expand All @@ -113,11 +131,13 @@ TEST(TestDriver, checkDataFormat_ASCII)
// Expect to check correctly when read data in ASCII format
auto mock = create_serial_port_mock();

// 1st: invalid ascii data (timestamp is double)
// 2nd: correct ascii data (timestamp is int)
When(Method(mock, readFromDevice)).Do([](
unsigned char* buf, unsigned int buf_size) {
rt_usb_9axisimu::Consts consts;
std::array<std::string, consts.IMU_ASCII_DATA_SIZE> dummy_ascii_imu_data;
dummy_ascii_imu_data[consts.IMU_ASCII_TIMESTAMP] = "0";
std::vector<const char*> dummy_ascii_imu_data(consts.IMU_ASCII_DATA_SIZE);
dummy_ascii_imu_data[consts.IMU_ASCII_TIMESTAMP] = "0.0";
dummy_ascii_imu_data[consts.IMU_ASCII_GYRO_X] = "0.000000";
dummy_ascii_imu_data[consts.IMU_ASCII_GYRO_Y] = "0.000000";
dummy_ascii_imu_data[consts.IMU_ASCII_GYRO_Z] = "0.000000";
Expand All @@ -128,26 +148,56 @@ TEST(TestDriver, checkDataFormat_ASCII)
dummy_ascii_imu_data[consts.IMU_ASCII_MAG_Y] = "0.000000";
dummy_ascii_imu_data[consts.IMU_ASCII_MAG_Z] = "0.000000";
dummy_ascii_imu_data[consts.IMU_ASCII_TEMP] = "0.000000";
std::string str = "";
std::string split_char = ",";
const char split_char = ',';
const char newline_char = '\n';
int char_count = 0;
for(int i = 0; i < consts.IMU_ASCII_DATA_SIZE; i++) {
str += dummy_ascii_imu_data[i];
if(i != consts.IMU_ASCII_DATA_SIZE - 1) str += split_char;
for(int j = 0; j < (int)strlen(dummy_ascii_imu_data.at(i)); j++) {
buf[char_count] = (unsigned char)dummy_ascii_imu_data.at(i)[j];
char_count++;
}
if(i != consts.IMU_ASCII_DATA_SIZE - 1) buf[char_count] = split_char;
else buf[char_count] = newline_char;
char_count++;
}
for(int i = 0; i < int(str.length()); i++) {
buf[i] = str[i];
buf_size = char_count;
return buf_size;
}).Do([](
unsigned char* buf, unsigned int buf_size) {
rt_usb_9axisimu::Consts consts;
std::vector<const char*> dummy_ascii_imu_data(consts.IMU_ASCII_DATA_SIZE);
dummy_ascii_imu_data[consts.IMU_ASCII_TIMESTAMP] = "0";
dummy_ascii_imu_data[consts.IMU_ASCII_GYRO_X] = "0.000000";
dummy_ascii_imu_data[consts.IMU_ASCII_GYRO_Y] = "0.000000";
dummy_ascii_imu_data[consts.IMU_ASCII_GYRO_Z] = "0.000000";
dummy_ascii_imu_data[consts.IMU_ASCII_ACC_X] = "0.000000";
dummy_ascii_imu_data[consts.IMU_ASCII_ACC_Y] = "0.000000";
dummy_ascii_imu_data[consts.IMU_ASCII_ACC_Z] = "0.000000";
dummy_ascii_imu_data[consts.IMU_ASCII_MAG_X] = "0.000000";
dummy_ascii_imu_data[consts.IMU_ASCII_MAG_Y] = "0.000000";
dummy_ascii_imu_data[consts.IMU_ASCII_MAG_Z] = "0.000000";
dummy_ascii_imu_data[consts.IMU_ASCII_TEMP] = "0.000000";
const char split_char = ',';
const char newline_char = '\n';
int char_count = 0;
for(int i = 0; i < consts.IMU_ASCII_DATA_SIZE; i++) {
for(int j = 0; j < (int)strlen(dummy_ascii_imu_data.at(i)); j++) {
buf[char_count] = (unsigned char)dummy_ascii_imu_data.at(i)[j];
char_count++;
}
if(i != consts.IMU_ASCII_DATA_SIZE - 1) buf[char_count] = split_char;
else buf[char_count] = newline_char;
char_count++;
}
buf_size = consts.IMU_BIN_DATA_SIZE;
buf_size = char_count;
return buf_size;
});

RtUsb9axisimuRosDriver driver(
std::unique_ptr<SerialPort>(&mock.get()));

driver.checkDataFormat();
driver.checkDataFormat();

EXPECT_TRUE(driver.hasCompletedFormatCheck());
EXPECT_TRUE(driver.hasAsciiDataFormat());
EXPECT_FALSE(driver.hasBinaryDataFormat());
}
Expand All @@ -157,15 +207,15 @@ TEST(TestDriver, checkDataFormat_not_Binary_or_ASCII)
// Expect to check correctly when read data in not Binary or ASCII format
auto mock = create_serial_port_mock();

When(Method(mock, readFromDevice)).Do([](
// always invalid data (not binary or ascii)
When(Method(mock, readFromDevice)).AlwaysDo([](
unsigned char* buf, unsigned int buf_size) {
rt_usb_9axisimu::Consts consts;
unsigned char dummy_data_not_binary_or_ascii[] =
"dummy_data_not_binary_or_ascii";
for(int i = 0; i < int(sizeof(dummy_data_not_binary_or_ascii)); i++) {
for(int i = 0; i < (int)sizeof(dummy_data_not_binary_or_ascii); i++) {
buf[i] = dummy_data_not_binary_or_ascii[i];
}
buf_size = consts.IMU_BIN_DATA_SIZE;
buf_size = strlen((char*)buf);
return buf_size;
});

Expand All @@ -174,7 +224,6 @@ TEST(TestDriver, checkDataFormat_not_Binary_or_ASCII)

driver.checkDataFormat();

EXPECT_FALSE(driver.hasCompletedFormatCheck());
EXPECT_FALSE(driver.hasBinaryDataFormat());
EXPECT_FALSE(driver.hasAsciiDataFormat());
}
Loading