34 #include <nav_msgs/Odometry.h>
35 #include <sensor_msgs/Imu.h>
39 #include <gtest/gtest.h>
55 nav_msgs::Odometry& odom_raw,
56 sensor_msgs::Imu& imu)
61 for (
int i = 0; i < 1000 &&
ros::ok(); ++i)
64 imu.header.stamp = odom_raw.header.stamp +
ros::Duration(0.0001);
73 return static_cast<bool>(
odom_);
76 nav_msgs::Odometry& odom_raw,
77 sensor_msgs::Imu& imu,
78 const double dt,
const int steps)
87 odom_raw.pose.pose.orientation =
90 tf2::Quaternion(tf2::Vector3(0.0, 0.0, 1.0), dt * odom_raw.twist.twist.angular.z));
96 tf2::Quaternion(tf2::Vector3(0.0, 0.0, 1.0), dt * imu.angular_velocity.z));
98 const double yaw =
tf2::getYaw(odom_raw.pose.pose.orientation);
99 odom_raw.pose.pose.position.x += cos(yaw) * dt * odom_raw.twist.twist.linear.x;
100 odom_raw.pose.pose.position.y += sin(yaw) * dt * odom_raw.twist.twist.linear.x;
113 nav_msgs::Odometry& odom_raw,
114 sensor_msgs::Imu& imu,
141 nav_msgs::Odometry::ConstPtr odom_prev =
odom_;
146 if (odom_prev ==
odom_)
162 void cbOdom(
const nav_msgs::Odometry::ConstPtr& msg)
172 const double dt = 0.01;
173 const int steps = 200;
175 nav_msgs::Odometry odom_raw;
176 odom_raw.header.frame_id =
"odom";
177 odom_raw.pose.pose.orientation.w = 1;
179 sensor_msgs::Imu imu;
180 imu.header.frame_id =
"base_link";
181 imu.orientation.w = 1;
182 imu.linear_acceleration.z = 9.8;
184 ASSERT_TRUE(initializeTrackOdometry(odom_raw, imu));
187 odom_raw.twist.twist.linear.x = 0.5;
188 ASSERT_TRUE(run(odom_raw, imu, dt, steps));
190 odom_raw.twist.twist.linear.x = 0.0;
191 stepAndPublish(odom_raw, imu, dt);
195 ASSERT_NEAR(odom_->pose.pose.position.x, 1.0, 1e-3);
196 ASSERT_NEAR(odom_->pose.pose.position.y, 0.0, 1e-3);
197 ASSERT_NEAR(odom_->pose.pose.position.z, 0.0, 1e-3);
198 ASSERT_NEAR(
tf2::getYaw(odom_->pose.pose.orientation), 0.0, 1e-3);
201 imu.angular_velocity.z = M_PI * 0.25;
202 odom_raw.twist.twist.angular.z = imu.angular_velocity.z * 1.1;
203 ASSERT_TRUE(run(odom_raw, imu, dt, steps));
205 imu.angular_velocity.z = 0;
206 odom_raw.twist.twist.angular.z = 0;
208 stepAndPublish(odom_raw, imu, dt);
212 ASSERT_NEAR(odom_->pose.pose.position.x, 1.0, 1e-2);
213 ASSERT_NEAR(odom_->pose.pose.position.y, 0.0, 1e-2);
214 ASSERT_NEAR(odom_->pose.pose.position.z, 0.0, 1e-2);
215 ASSERT_NEAR(
tf2::getYaw(odom_->pose.pose.orientation), M_PI / 2, 1e-2);
218 odom_raw.twist.twist.linear.x = 0.5;
219 ASSERT_TRUE(run(odom_raw, imu, dt, steps));
221 odom_raw.twist.twist.linear.x = 0.0;
222 stepAndPublish(odom_raw, imu, dt);
226 ASSERT_NEAR(odom_->pose.pose.position.x, 1.0, 5e-2);
227 ASSERT_NEAR(odom_->pose.pose.position.y, 1.0, 5e-2);
228 ASSERT_NEAR(odom_->pose.pose.position.z, 0.0, 5e-2);
229 ASSERT_NEAR(
tf2::getYaw(odom_->pose.pose.orientation), M_PI / 2, 1e-2);
234 const std::string ns_postfix(GetParam());
235 initializeNode(
"no_z_filter" + ns_postfix);
237 const double dt = 0.01;
238 const int steps = 200;
240 nav_msgs::Odometry odom_raw;
241 odom_raw.header.frame_id =
"odom";
242 odom_raw.pose.pose.orientation.w = 1;
244 sensor_msgs::Imu imu;
245 imu.header.frame_id =
"base_link";
246 imu.orientation.y = sin(-M_PI / 4);
247 imu.orientation.w = cos(-M_PI / 4);
248 imu.linear_acceleration.x = -9.8;
250 ASSERT_TRUE(initializeTrackOdometry(odom_raw, imu));
253 odom_raw.twist.twist.linear.x = 0.5;
254 ASSERT_TRUE(run(odom_raw, imu, dt, steps));
256 odom_raw.twist.twist.linear.x = 0.0;
257 stepAndPublish(odom_raw, imu, dt);
261 ASSERT_NEAR(odom_->pose.pose.position.x, 0.0, 1e-3);
262 ASSERT_NEAR(odom_->pose.pose.position.y, 0.0, 1e-3);
263 ASSERT_NEAR(odom_->pose.pose.position.z, 1.0, 1e-3);
268 const std::string ns_postfix(GetParam());
269 initializeNode(
"z_filter" + ns_postfix);
271 const double dt = 0.01;
272 const int steps = 200;
274 nav_msgs::Odometry odom_raw;
275 odom_raw.header.frame_id =
"odom";
276 odom_raw.pose.pose.orientation.w = 1;
278 sensor_msgs::Imu imu;
279 imu.header.frame_id =
"base_link";
280 imu.orientation.y = sin(-M_PI / 4);
281 imu.orientation.w = cos(-M_PI / 4);
282 imu.linear_acceleration.x = -9.8;
284 ASSERT_TRUE(initializeTrackOdometry(odom_raw, imu));
287 odom_raw.twist.twist.linear.x = 0.5;
288 ASSERT_TRUE(run(odom_raw, imu, dt, steps));
290 odom_raw.twist.twist.linear.x = 0.0;
291 stepAndPublish(odom_raw, imu, dt);
295 ASSERT_NEAR(odom_->pose.pose.position.z, 1.0 - 1.0 / M_E, 5e-2);
300 ::testing::Values(
"",
"_old_param"));
302 int main(
int argc,
char** argv)
304 testing::InitGoogleTest(&argc, argv);
305 ros::init(argc, argv,
"test_track_odometry");
307 return RUN_ALL_TESTS();