|
| 1 | +/** |
| 2 | + * Copyright (C) 2024 Stylianos Piperakis, Ownage Dynamics L.P. |
| 3 | + * Serow is free software: you can redistribute it and/or modify it under the terms of the GNU |
| 4 | + * General Public License as published by the Free Software Foundation, version 3. |
| 5 | + * |
| 6 | + * Serow is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without |
| 7 | + * even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU |
| 8 | + * General Public License for more details. |
| 9 | + * |
| 10 | + * You should have received a copy of the GNU General Public License along with Serow. If not, |
| 11 | + * see <https://www.gnu.org/licenses/>. |
| 12 | + **/ |
| 13 | +#include <gtest/gtest.h> |
| 14 | + |
| 15 | +#include <chrono> |
| 16 | +#include <fstream> |
| 17 | +#include <iostream> |
| 18 | +#include <map> |
| 19 | +#include <serow/Serow.hpp> |
| 20 | +#include <sstream> |
| 21 | +#include <string> |
| 22 | + |
| 23 | +TEST(SerowTests, Go2Test) { |
| 24 | + serow::Serow SEROW("../../config/go1.json"); |
| 25 | + const double mass = 12; // kg |
| 26 | + const double g = 9.81; // m/s^2 |
| 27 | + const double mg = mass * g; // N |
| 28 | + const double bias = 14; // potatos |
| 29 | + const double den = 172.91 - 4 * bias; // potatos |
| 30 | + |
| 31 | + std::fstream file("../../test/data/go1.csv", std::ios::in); |
| 32 | + if (!file.is_open()) { |
| 33 | + throw std::runtime_error("Could not open file"); |
| 34 | + return; |
| 35 | + } |
| 36 | + // Read the CSV file |
| 37 | + std::vector<std::vector<std::string>> data; |
| 38 | + std::vector<std::string> row; |
| 39 | + std::string line, word; |
| 40 | + while (std::getline(file, line)) { |
| 41 | + row.clear(); |
| 42 | + std::stringstream str(line); |
| 43 | + |
| 44 | + while (std::getline(str, word, ',')) { |
| 45 | + row.push_back(word); |
| 46 | + } |
| 47 | + data.push_back(row); |
| 48 | + } |
| 49 | + file.close(); |
| 50 | + |
| 51 | + // Parse the data, create the measurements, and run the filtering loop |
| 52 | + for (size_t i = 1; i < data.size(); i++) { |
| 53 | + double timestamp = std::stod(data[i][0]) * 1e-9; // s |
| 54 | + |
| 55 | + std::map<std::string, serow::ForceTorqueMeasurement> force_torque; |
| 56 | + Eigen::Vector3d force = |
| 57 | + Eigen::Vector3d(0, 0, std::clamp((std::stod(data[i][1]) - bias) * mg / den, 0.0, mg)); |
| 58 | + force_torque.insert( |
| 59 | + {"FR_foot", serow::ForceTorqueMeasurement{.timestamp = timestamp, .force = force}}); |
| 60 | + |
| 61 | + force = |
| 62 | + Eigen::Vector3d(0, 0, std::clamp((std::stod(data[i][2]) - bias) * mg / den, 0.0, mg)); |
| 63 | + force_torque.insert( |
| 64 | + {"FL_foot", serow::ForceTorqueMeasurement{.timestamp = timestamp, .force = force}}); |
| 65 | + |
| 66 | + force = |
| 67 | + Eigen::Vector3d(0, 0, std::clamp((std::stod(data[i][3]) - bias) * mg / den, 0.0, mg)); |
| 68 | + force_torque.insert( |
| 69 | + {"RR_foot", serow::ForceTorqueMeasurement{.timestamp = timestamp, .force = force}}); |
| 70 | + |
| 71 | + force = |
| 72 | + Eigen::Vector3d(0, 0, std::clamp((std::stod(data[i][4]) - bias) * mg / den, 0.0, mg)); |
| 73 | + force_torque.insert( |
| 74 | + {"RL_foot", serow::ForceTorqueMeasurement{.timestamp = timestamp, .force = force}}); |
| 75 | + |
| 76 | + serow::ImuMeasurement imu; |
| 77 | + imu.timestamp = timestamp; |
| 78 | + imu.linear_acceleration = |
| 79 | + Eigen::Vector3d(std::stod(data[i][5]), std::stod(data[i][6]), std::stod(data[i][7])); |
| 80 | + imu.angular_velocity = |
| 81 | + Eigen::Vector3d(std::stod(data[i][8]), std::stod(data[i][9]), std::stod(data[i][10])); |
| 82 | + |
| 83 | + std::map<std::string, serow::JointMeasurement> joints; |
| 84 | + joints.insert( |
| 85 | + {"FR_hip_joint", |
| 86 | + serow::JointMeasurement{.timestamp = timestamp, .position = std::stod(data[i][11])}}); |
| 87 | + joints.insert( |
| 88 | + {"FR_thigh_joint", |
| 89 | + serow::JointMeasurement{.timestamp = timestamp, .position = std::stod(data[i][12])}}); |
| 90 | + joints.insert( |
| 91 | + {"FR_calf_joint", |
| 92 | + serow::JointMeasurement{.timestamp = timestamp, .position = std::stod(data[i][13])}}); |
| 93 | + joints.insert( |
| 94 | + {"FL_hip_joint", |
| 95 | + serow::JointMeasurement{.timestamp = timestamp, .position = std::stod(data[i][14])}}); |
| 96 | + joints.insert( |
| 97 | + {"FL_thigh_joint", |
| 98 | + serow::JointMeasurement{.timestamp = timestamp, .position = std::stod(data[i][15])}}); |
| 99 | + joints.insert( |
| 100 | + {"FL_calf_joint", |
| 101 | + serow::JointMeasurement{.timestamp = timestamp, .position = std::stod(data[i][16])}}); |
| 102 | + joints.insert( |
| 103 | + {"RR_hip_joint", |
| 104 | + serow::JointMeasurement{.timestamp = timestamp, .position = std::stod(data[i][17])}}); |
| 105 | + joints.insert( |
| 106 | + {"RR_thigh_joint", |
| 107 | + serow::JointMeasurement{.timestamp = timestamp, .position = std::stod(data[i][18])}}); |
| 108 | + joints.insert( |
| 109 | + {"RR_calf_joint", |
| 110 | + serow::JointMeasurement{.timestamp = timestamp, .position = std::stod(data[i][19])}}); |
| 111 | + joints.insert( |
| 112 | + {"RL_hip_joint", |
| 113 | + serow::JointMeasurement{.timestamp = timestamp, .position = std::stod(data[i][20])}}); |
| 114 | + joints.insert( |
| 115 | + {"RL_thigh_joint", |
| 116 | + serow::JointMeasurement{.timestamp = timestamp, .position = std::stod(data[i][21])}}); |
| 117 | + joints.insert( |
| 118 | + {"RL_calf_joint", |
| 119 | + serow::JointMeasurement{.timestamp = timestamp, .position = std::stod(data[i][22])}}); |
| 120 | + |
| 121 | + auto t0 = std::chrono::high_resolution_clock::now(); |
| 122 | + SEROW.filter(imu, joints, force_torque); |
| 123 | + auto t1 = std::chrono::high_resolution_clock::now(); |
| 124 | + auto duration = std::chrono::duration_cast<std::chrono::microseconds>(t1 - t0); |
| 125 | + std::cout << "SEROW filtering loop duration " << duration.count() << " us " << std::endl; |
| 126 | + t0 = std::chrono::high_resolution_clock::now(); |
| 127 | + auto state = SEROW.getState(); |
| 128 | + t1 = std::chrono::high_resolution_clock::now(); |
| 129 | + duration = std::chrono::duration_cast<std::chrono::microseconds>(t1 - t0); |
| 130 | + std::cout << "SEROW get state duration " << duration.count() << " us " << std::endl; |
| 131 | + if (!state.has_value()) { |
| 132 | + continue; |
| 133 | + } |
| 134 | + EXPECT_FALSE(state->getBasePosition() != state->getBasePosition()); |
| 135 | + EXPECT_FALSE(state->getBaseLinearVelocity() != state->getBaseLinearVelocity()); |
| 136 | + EXPECT_FALSE(state->getBaseOrientation() != state->getBaseOrientation()); |
| 137 | + for (const auto& cf : state->getContactsFrame()) { |
| 138 | + if (state->getContactPosition(cf)) { |
| 139 | + EXPECT_FALSE(*state->getContactPosition(cf) != *state->getContactPosition(cf)); |
| 140 | + } |
| 141 | + } |
| 142 | + EXPECT_FALSE(state->getCoMPosition() != state->getCoMPosition()); |
| 143 | + EXPECT_FALSE(state->getCoMLinearVelocity() != state->getCoMLinearVelocity()); |
| 144 | + EXPECT_FALSE(state->getCoMExternalForces() != state->getCoMExternalForces()); |
| 145 | + |
| 146 | + std::cout << "Base position " << state->getBasePosition().transpose() << std::endl; |
| 147 | + std::cout << "Base velocity " << state->getBaseLinearVelocity().transpose() << std::endl; |
| 148 | + std::cout << "Base orientation " << state->getBaseOrientation() << std::endl; |
| 149 | + std::cout << "IMU gyro bias " << state->getImuAngularVelocityBias().transpose() |
| 150 | + << std::endl; |
| 151 | + std::cout << "IMU acc bias " << state->getImuLinearAccelerationBias().transpose() |
| 152 | + << std::endl; |
| 153 | + for (const auto& cf : state->getContactsFrame()) { |
| 154 | + if (!state->getContactPosition(cf)) { |
| 155 | + continue; |
| 156 | + } |
| 157 | + std::cout << cf << " contact position " << state->getContactPosition(cf)->transpose() |
| 158 | + << std::endl; |
| 159 | + } |
| 160 | + std::cout << "CoM position " << state->getCoMPosition().transpose() << std::endl; |
| 161 | + std::cout << "CoM linear velocity " << state->getCoMLinearVelocity().transpose() |
| 162 | + << std::endl; |
| 163 | + std::cout << "CoM external forces " << state->getCoMExternalForces().transpose() |
| 164 | + << std::endl; |
| 165 | + } |
| 166 | +} |
0 commit comments