twist2odom_test.cpp 2.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990
  1. /*
  2. * Copyright (c) 2019 Autoware Foundation, AutonomouStuff
  3. * All rights reserved.
  4. *
  5. * Licensed under the Apache License, Version 2.0 (the "License"); you may not use this file
  6. * except in compliance with the License. You may obtain a copy of the License at
  7. *
  8. * http://www.apache.org/licenses/LICENSE-2.0
  9. */
  10. #include <gtest/gtest.h>
  11. #include <ros/ros.h>
  12. #include <geometry_msgs/TwistStamped.h>
  13. #include <nav_msgs/Odometry.h>
  14. #include "twist2odom/twist2odom.h"
  15. class Twist2OdomTestSuite : public ::testing::Test
  16. {
  17. public:
  18. Twist2OdomTestSuite()
  19. {
  20. pub_twist_ = nh_.advertise<geometry_msgs::TwistStamped>("current_twist", 1);
  21. sub_odom_ = nh_.subscribe("current_odom", 1, &Twist2OdomTestSuite::callbackFromOdom, this);
  22. }
  23. void callbackFromOdom(const nav_msgs::OdometryConstPtr& msg)
  24. {
  25. current_odom_ptr_ = std::make_shared<nav_msgs::Odometry>(*msg);
  26. ROS_ERROR("Got to the callback!");
  27. }
  28. void resetCurrentOdom()
  29. {
  30. current_odom_ptr_ = nullptr;
  31. }
  32. twist2odom::Twist2Odom t2o_;
  33. ros::NodeHandle nh_;
  34. ros::Publisher pub_twist_;
  35. ros::Subscriber sub_odom_;
  36. std::shared_ptr<nav_msgs::Odometry> current_odom_ptr_;
  37. };
  38. TEST_F(Twist2OdomTestSuite, simpleTwistPub)
  39. {
  40. while (true)
  41. {
  42. if (pub_twist_.getNumSubscribers() < 1 &&
  43. sub_odom_.getNumPublishers() < 1)
  44. ros::Duration(0.1).sleep();
  45. else
  46. break;
  47. }
  48. geometry_msgs::TwistStamped twist;
  49. twist.twist.linear.x = 1.0;
  50. twist.twist.linear.y = 2.0;
  51. twist.twist.linear.z = 3.0;
  52. twist.twist.angular.x = 1.0;
  53. twist.twist.angular.y = 2.0;
  54. twist.twist.angular.z = 3.0;
  55. for (int i = 0; i < 10; ++i)
  56. {
  57. twist.header.stamp = ros::Time::now();
  58. pub_twist_.publish(twist);
  59. ros::spinOnce();
  60. ros::Duration(0.1).sleep();
  61. }
  62. ASSERT_FALSE(current_odom_ptr_ == nullptr);
  63. ASSERT_FLOAT_EQ(current_odom_ptr_->twist.twist.linear.x, 1.0);
  64. ASSERT_FLOAT_EQ(current_odom_ptr_->twist.twist.linear.y, 2.0);
  65. ASSERT_FLOAT_EQ(current_odom_ptr_->twist.twist.linear.z, 3.0);
  66. ASSERT_FLOAT_EQ(current_odom_ptr_->twist.twist.angular.x, 1.0);
  67. ASSERT_FLOAT_EQ(current_odom_ptr_->twist.twist.angular.y, 2.0);
  68. ASSERT_FLOAT_EQ(current_odom_ptr_->twist.twist.angular.z, 3.0);
  69. resetCurrentOdom();
  70. }
  71. int main(int argc, char** argv)
  72. {
  73. testing::InitGoogleTest(&argc, argv);
  74. ros::init(argc, argv, "Twist2OdomTestSuite");
  75. return RUN_ALL_TESTS();
  76. }