7 #include <gtest/gtest.h>
8 #include <sensor_msgs/Imu.h>
12 #define G_TO_METERS_PER_SECOND_SQUARED 9.80665
13 using namespace Eigen;
59 std::uint32_t lpos = msgCount_;
61 linAccXSamples_.conservativeResize(msgCount_);
62 linAccYSamples_.conservativeResize(msgCount_);
63 linAccZSamples_.conservativeResize(msgCount_);
64 angVelXSamples_.conservativeResize(msgCount_);
65 angVelYSamples_.conservativeResize(msgCount_);
66 angVelZSamples_.conservativeResize(msgCount_);
68 linAccXSamples_(lpos) =
msg->linear_acceleration.x;
69 linAccYSamples_(lpos) =
msg->linear_acceleration.y;
70 linAccZSamples_(lpos) =
msg->linear_acceleration.z;
71 angVelXSamples_(lpos) =
msg->angular_velocity.x;
72 angVelYSamples_(lpos) =
msg->angular_velocity.y;
73 angVelZSamples_(lpos) =
msg->angular_velocity.z;
79 SCOPED_TRACE(
"SignalQualityImu");
81 ASSERT_EQ(nh_.getParam(
"topic_name", topicName_),
true);
84 ASSERT_EQ(nh_.getParam(
"test_duration", testDuration_),
true);
89 if (HasFatalFailure())
91 FAIL() <<
"Fatal errors occurred.\n";
96 EXPECT_GT(msgCount_, 0U);
97 double linacc_xsamples_mean, linacc_ysamples_mean, linacc_zsamples_mean, angvel_xsamples_mean, angvel_ysamples_mean,
98 angvel_zsamples_mean, linacc_mean, angvel_mean;
99 linacc_xsamples_mean = linAccXSamples_.mean();
100 linacc_ysamples_mean = linAccYSamples_.mean();
101 linacc_zsamples_mean = linAccZSamples_.mean();
103 linacc_mean = std::sqrt(std::pow(linacc_xsamples_mean, 2) + std::pow(linacc_ysamples_mean, 2) +
104 std::pow(linacc_zsamples_mean, 2));
105 angvel_xsamples_mean = angVelXSamples_.mean();
106 angvel_ysamples_mean = angVelYSamples_.mean();
107 angvel_zsamples_mean = angVelZSamples_.mean();
109 angvel_mean = std::sqrt(std::pow(angvel_xsamples_mean, 2) + std::pow(angvel_ysamples_mean, 2) +
110 std::pow(angvel_zsamples_mean, 2));
111 linAccXSamples_ = linAccXSamples_.array() - linAccXSamples_.mean();
112 double sigma_ax = std::sqrt(linAccXSamples_.squaredNorm() / msgCount_);
113 linAccYSamples_ = linAccYSamples_.array() - linAccYSamples_.mean();
114 double sigma_ay = std::sqrt(linAccYSamples_.squaredNorm() / msgCount_);
115 linAccZSamples_ = linAccZSamples_.array() - linAccZSamples_.mean();
116 double sigma_az = std::sqrt(linAccZSamples_.squaredNorm() / msgCount_);
117 angVelXSamples_ = angVelXSamples_.array() - angVelXSamples_.mean();
118 double sigma_vx = std::sqrt(angVelXSamples_.squaredNorm() / msgCount_);
119 angVelYSamples_ = angVelYSamples_.array() - angVelYSamples_.mean();
120 double sigma_vy = std::sqrt(angVelYSamples_.squaredNorm() / msgCount_);
121 angVelZSamples_ = angVelZSamples_.array() - angVelZSamples_.mean();
122 double sigma_vz = std::sqrt(angVelZSamples_.squaredNorm() / msgCount_);
124 double max_sigma_axy, max_sigma_az, max_sigma_vxy, max_sigma_vz, mean_dev_lin_acc, mean_dev_ang_vel;
125 ASSERT_EQ(nh_.getParam(
"max_sigma_axy", max_sigma_axy),
true);
126 ASSERT_EQ(nh_.getParam(
"max_sigma_az", max_sigma_az),
true);
127 ASSERT_EQ(nh_.getParam(
"max_sigma_vxy", max_sigma_vxy),
true);
128 ASSERT_EQ(nh_.getParam(
"max_sigma_vz", max_sigma_vz),
true);
129 ASSERT_EQ(nh_.getParam(
"mean_dev_lin_acc", mean_dev_lin_acc),
true);
130 ASSERT_EQ(nh_.getParam(
"mean_dev_ang_vel", mean_dev_ang_vel),
true);
134 ASSERT_NEAR(angvel_mean, 0.0, mean_dev_ang_vel);
137 ASSERT_GT(sigma_ax, 1e-7);
138 ASSERT_GT(sigma_ay, 1e-7);
139 ASSERT_GT(sigma_az, 1e-7);
140 ASSERT_GT(sigma_vx, 1e-7);
141 ASSERT_GT(sigma_vy, 1e-7);
142 ASSERT_GT(sigma_vz, 1e-7);
143 ASSERT_LT(sigma_ax, max_sigma_axy);
144 ASSERT_LT(sigma_ay, max_sigma_axy);
145 ASSERT_LT(sigma_az, max_sigma_az);
146 ASSERT_LT(sigma_vx, max_sigma_vxy);
147 ASSERT_LT(sigma_vy, max_sigma_vxy);
148 ASSERT_LT(sigma_vz, max_sigma_vz);