6 #include <gtest/gtest.h>
9 #include <sensor_msgs/NavSatFix.h>
10 #include <sensor_msgs/Imu.h>
11 #include <geometry_msgs/TwistWithCovarianceStamped.h>
17 #include <arpa/inet.h>
18 #include <sys/socket.h>
24 #include "../src/dispatch.h"
50 void recvGpsVel(
const geometry_msgs::TwistWithCovarianceStamped::ConstPtr& msg) {
g_msg_vel.set(*msg); }
56 const uint8_t *ptr = ((uint8_t*)&packet) + 1;
58 for (; ptr < &packet.
chksum1; ptr++) {
62 for (; ptr < &packet.
chksum2; ptr++) {
66 for (; ptr < &packet.
chksum3; ptr++) {
77 fd = socket(AF_INET, SOCK_DGRAM, IPPROTO_UDP);
80 struct sockaddr_in si_other;
81 memset(&si_other, 0x00,
sizeof(si_other));
82 si_other.sin_family = AF_INET;
83 si_other.sin_port = htons(
g_port);
84 if (inet_aton(
g_ip_address.c_str(), &si_other.sin_addr)) {
85 if (sendto(fd, &packet,
sizeof(packet), 0, (
struct sockaddr *) &si_other,
sizeof(si_other)) ==
sizeof(packet)) {
94 static inline double SQUARE(
double x) {
return x * x; }
142 memset(&packet, 0x00,
sizeof(packet));
175 memset(&packet, 0x00,
sizeof(packet));
192 EXPECT_NEAR((
g_msg_fix.get().header.stamp - stamp).toSec(), 0, 0.01);
201 memset(&packet, 0x00,
sizeof(packet));
215 EXPECT_EQ(
g_msg_fix.get().status.status, sensor_msgs::NavSatStatus::STATUS_NO_FIX);
216 EXPECT_EQ(
g_msg_fix.get().status.service, sensor_msgs::NavSatStatus::SERVICE_GPS);
220 EXPECT_EQ(
g_msg_fix.get().position_covariance_type, sensor_msgs::NavSatFix::COVARIANCE_TYPE_UNKNOWN);
221 EXPECT_EQ(
g_msg_fix.get().position_covariance[0], 0);
222 EXPECT_EQ(
g_msg_fix.get().position_covariance[1], 0);
223 EXPECT_EQ(
g_msg_fix.get().position_covariance[2], 0);
224 EXPECT_EQ(
g_msg_fix.get().position_covariance[3], 0);
225 EXPECT_EQ(
g_msg_fix.get().position_covariance[4], 0);
226 EXPECT_EQ(
g_msg_fix.get().position_covariance[5], 0);
227 EXPECT_EQ(
g_msg_fix.get().position_covariance[6], 0);
228 EXPECT_EQ(
g_msg_fix.get().position_covariance[7], 0);
229 EXPECT_EQ(
g_msg_fix.get().position_covariance[8], 0);
232 memset(&packet.
chan, 0x00,
sizeof(packet.
chan));
242 EXPECT_EQ(
g_msg_fix.get().status.status, sensor_msgs::NavSatStatus::STATUS_GBAS_FIX);
243 EXPECT_EQ(
g_msg_fix.get().status.service, sensor_msgs::NavSatStatus::SERVICE_GPS);
247 EXPECT_EQ(
g_msg_fix.get().position_covariance_type, sensor_msgs::NavSatFix::COVARIANCE_TYPE_UNKNOWN);
248 EXPECT_EQ(
g_msg_fix.get().position_covariance[0], 0);
249 EXPECT_EQ(
g_msg_fix.get().position_covariance[1], 0);
250 EXPECT_EQ(
g_msg_fix.get().position_covariance[2], 0);
251 EXPECT_EQ(
g_msg_fix.get().position_covariance[3], 0);
252 EXPECT_EQ(
g_msg_fix.get().position_covariance[4], 0);
253 EXPECT_EQ(
g_msg_fix.get().position_covariance[5], 0);
254 EXPECT_EQ(
g_msg_fix.get().position_covariance[6], 0);
255 EXPECT_EQ(
g_msg_fix.get().position_covariance[7], 0);
256 EXPECT_EQ(
g_msg_fix.get().position_covariance[8], 0);
259 memset(&packet.
chan, 0x00,
sizeof(packet.
chan));
272 EXPECT_EQ(
g_msg_fix.get().status.status, sensor_msgs::NavSatStatus::STATUS_GBAS_FIX);
273 EXPECT_EQ(
g_msg_fix.get().status.service, sensor_msgs::NavSatStatus::SERVICE_GPS);
277 EXPECT_EQ(
g_msg_fix.get().position_covariance_type, sensor_msgs::NavSatFix::COVARIANCE_TYPE_DIAGONAL_KNOWN);
279 EXPECT_EQ(
g_msg_fix.get().position_covariance[1], 0);
280 EXPECT_EQ(
g_msg_fix.get().position_covariance[2], 0);
281 EXPECT_EQ(
g_msg_fix.get().position_covariance[3], 0);
283 EXPECT_EQ(
g_msg_fix.get().position_covariance[5], 0);
284 EXPECT_EQ(
g_msg_fix.get().position_covariance[6], 0);
285 EXPECT_EQ(
g_msg_fix.get().position_covariance[7], 0);
289 memset(&packet.
chan, 0x00,
sizeof(packet.
chan));
302 EXPECT_EQ(
g_msg_fix.get().status.status, sensor_msgs::NavSatStatus::STATUS_GBAS_FIX);
303 EXPECT_EQ(
g_msg_fix.get().status.service, sensor_msgs::NavSatStatus::SERVICE_GPS);
307 EXPECT_EQ(
g_msg_fix.get().position_covariance_type, sensor_msgs::NavSatFix::COVARIANCE_TYPE_UNKNOWN);
308 EXPECT_EQ(
g_msg_fix.get().position_covariance[0], 0);
309 EXPECT_EQ(
g_msg_fix.get().position_covariance[1], 0);
310 EXPECT_EQ(
g_msg_fix.get().position_covariance[2], 0);
311 EXPECT_EQ(
g_msg_fix.get().position_covariance[3], 0);
312 EXPECT_EQ(
g_msg_fix.get().position_covariance[4], 0);
313 EXPECT_EQ(
g_msg_fix.get().position_covariance[5], 0);
314 EXPECT_EQ(
g_msg_fix.get().position_covariance[6], 0);
315 EXPECT_EQ(
g_msg_fix.get().position_covariance[7], 0);
316 EXPECT_EQ(
g_msg_fix.get().position_covariance[8], 0);
325 memset(&packet, 0x00,
sizeof(packet));
341 EXPECT_EQ(
g_msg_vel.get().twist.twist.linear.z, (
double)packet.
vel_down * -1e-4);
342 for (
size_t i = 0; i <
g_msg_vel.get().twist.covariance.size(); i++) {
343 EXPECT_EQ(
g_msg_vel.get().twist.covariance[i], 0);
347 memset(&packet.
chan, 0x00,
sizeof(packet.
chan));
362 EXPECT_EQ(
g_msg_vel.get().twist.twist.linear.z, (
double)packet.
vel_down * -1e-4);
368 memset(&packet.
chan, 0x00,
sizeof(packet.
chan));
383 EXPECT_EQ(
g_msg_vel.get().twist.twist.linear.z, (
double)packet.
vel_down * -1e-4);
384 for (
size_t i = 0; i <
g_msg_vel.get().twist.covariance.size(); i++) {
385 EXPECT_EQ(
g_msg_vel.get().twist.covariance[i], 0);
395 memset(&packet, 0x00,
sizeof(packet));
407 packet.
pitch = -123456;
408 packet.
roll = 234567;
416 q.
setRPY((
double)packet.
roll * 1e-6, (
double)packet.
pitch * 1e-6, M_PI_2 - (
double)packet.
heading * 1e-6);
417 EXPECT_EQ(
g_msg_imu.get().orientation.w, q.w());
418 EXPECT_EQ(
g_msg_imu.get().orientation.x, q.x());
419 EXPECT_EQ(
g_msg_imu.get().orientation.y, q.y());
420 EXPECT_EQ(
g_msg_imu.get().orientation.z, q.z());
421 EXPECT_EQ(
g_msg_imu.get().linear_acceleration.x, (
double)packet.
accel_x * 1e-4);
422 EXPECT_EQ(
g_msg_imu.get().linear_acceleration.y, (
double)packet.
accel_y * 1e-4);
423 EXPECT_EQ(
g_msg_imu.get().linear_acceleration.z, (
double)packet.
accel_z * -1e-4);
424 EXPECT_EQ(
g_msg_imu.get().angular_velocity.x, (
double)packet.
gyro_x * 1e-5);
425 EXPECT_EQ(
g_msg_imu.get().angular_velocity.y, (
double)packet.
gyro_y * 1e-5);
426 EXPECT_EQ(
g_msg_imu.get().angular_velocity.z, (
double)packet.
gyro_z * -1e-5);
427 EXPECT_EQ(
g_msg_imu.get().angular_velocity_covariance[0], 0.0);
428 EXPECT_EQ(
g_msg_imu.get().angular_velocity_covariance[4], 0.0);
429 EXPECT_EQ(
g_msg_imu.get().angular_velocity_covariance[8], 0.0);
430 EXPECT_EQ(
g_msg_imu.get().linear_acceleration_covariance[0], 0.0);
431 EXPECT_EQ(
g_msg_imu.get().linear_acceleration_covariance[4], 0.0);
432 EXPECT_EQ(
g_msg_imu.get().linear_acceleration_covariance[8], 0.0);
433 EXPECT_EQ(
g_msg_imu.get().orientation_covariance[0], 0.0);
434 EXPECT_EQ(
g_msg_imu.get().orientation_covariance[4], 0.0);
435 EXPECT_EQ(
g_msg_imu.get().orientation_covariance[8], 0.0);
438 memset(&packet.
chan, 0x00,
sizeof(packet.
chan));
451 q.
setRPY((
double)packet.
roll * 1e-6, (
double)packet.
pitch * 1e-6, M_PI_2 - (
double)packet.
heading * 1e-6);
452 EXPECT_EQ(
g_msg_imu.get().orientation.w, q.w());
453 EXPECT_EQ(
g_msg_imu.get().orientation.x, q.x());
454 EXPECT_EQ(
g_msg_imu.get().orientation.y, q.y());
455 EXPECT_EQ(
g_msg_imu.get().orientation.z, q.z());
456 EXPECT_EQ(
g_msg_imu.get().linear_acceleration.x, (
double)packet.
accel_x * 1e-4);
457 EXPECT_EQ(
g_msg_imu.get().linear_acceleration.y, (
double)packet.
accel_y * 1e-4);
458 EXPECT_EQ(
g_msg_imu.get().linear_acceleration.z, (
double)packet.
accel_z * -1e-4);
459 EXPECT_EQ(
g_msg_imu.get().angular_velocity.x, (
double)packet.
gyro_x * 1e-5);
460 EXPECT_EQ(
g_msg_imu.get().angular_velocity.y, (
double)packet.
gyro_y * 1e-5);
461 EXPECT_EQ(
g_msg_imu.get().angular_velocity.z, (
double)packet.
gyro_z * -1e-5);
462 EXPECT_EQ(
g_msg_imu.get().angular_velocity_covariance[0], 0.0);
463 EXPECT_EQ(
g_msg_imu.get().angular_velocity_covariance[4], 0.0);
464 EXPECT_EQ(
g_msg_imu.get().angular_velocity_covariance[8], 0.0);
465 EXPECT_EQ(
g_msg_imu.get().linear_acceleration_covariance[0], 0.0);
466 EXPECT_EQ(
g_msg_imu.get().linear_acceleration_covariance[4], 0.0);
467 EXPECT_EQ(
g_msg_imu.get().linear_acceleration_covariance[8], 0.0);
473 memset(&packet.
chan, 0x00,
sizeof(packet.
chan));
486 q.
setRPY((
double)packet.
roll * 1e-6, (
double)packet.
pitch * 1e-6, M_PI_2 - (
double)packet.
heading * 1e-6);
487 EXPECT_EQ(
g_msg_imu.get().orientation.w, q.w());
488 EXPECT_EQ(
g_msg_imu.get().orientation.x, q.x());
489 EXPECT_EQ(
g_msg_imu.get().orientation.y, q.y());
490 EXPECT_EQ(
g_msg_imu.get().orientation.z, q.z());
491 EXPECT_EQ(
g_msg_imu.get().linear_acceleration.x, (
double)packet.
accel_x * 1e-4);
492 EXPECT_EQ(
g_msg_imu.get().linear_acceleration.y, (
double)packet.
accel_y * 1e-4);
493 EXPECT_EQ(
g_msg_imu.get().linear_acceleration.z, (
double)packet.
accel_z * -1e-4);
494 EXPECT_EQ(
g_msg_imu.get().angular_velocity.x, (
double)packet.
gyro_x * 1e-5);
495 EXPECT_EQ(
g_msg_imu.get().angular_velocity.y, (
double)packet.
gyro_y * 1e-5);
496 EXPECT_EQ(
g_msg_imu.get().angular_velocity.z, (
double)packet.
gyro_z * -1e-5);
497 EXPECT_EQ(
g_msg_imu.get().angular_velocity_covariance[0], 0.0);
498 EXPECT_EQ(
g_msg_imu.get().angular_velocity_covariance[4], 0.0);
499 EXPECT_EQ(
g_msg_imu.get().angular_velocity_covariance[8], 0.0);
500 EXPECT_EQ(
g_msg_imu.get().linear_acceleration_covariance[0], 0.0);
501 EXPECT_EQ(
g_msg_imu.get().linear_acceleration_covariance[4], 0.0);
502 EXPECT_EQ(
g_msg_imu.get().linear_acceleration_covariance[8], 0.0);
503 EXPECT_EQ(
g_msg_imu.get().orientation_covariance[0], 0.0);
504 EXPECT_EQ(
g_msg_imu.get().orientation_covariance[4], 0.0);
505 EXPECT_EQ(
g_msg_imu.get().orientation_covariance[8], 0.0);
509 int main(
int argc,
char **argv)
511 testing::InitGoogleTest(&argc, argv);
531 return RUN_ALL_TESTS();