footprint_tests.cpp 6.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182
  1. /*********************************************************************
  2. *
  3. * Software License Agreement (BSD License)
  4. *
  5. * Copyright (c) 2009, Willow Garage, Inc.
  6. * All rights reserved.
  7. *
  8. * Redistribution and use in source and binary forms, with or without
  9. * modification, are permitted provided that the following conditions
  10. * are met:
  11. *
  12. * * Redistributions of source code must retain the above copyright
  13. * notice, this list of conditions and the following disclaimer.
  14. * * Redistributions in binary form must reproduce the above
  15. * copyright notice, this list of conditions and the following
  16. * disclaimer in the documentation and/or other materials provided
  17. * with the distribution.
  18. * * Neither the name of Willow Garage, Inc. nor the names of its
  19. * contributors may be used to endorse or promote products derived
  20. * from this software without specific prior written permission.
  21. *
  22. * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
  23. * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
  24. * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
  25. * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
  26. * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
  27. * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
  28. * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
  29. * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
  30. * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
  31. * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
  32. * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
  33. * POSSIBILITY OF SUCH DAMAGE.
  34. *
  35. * Author: Dave Hershberger
  36. *********************************************************************/
  37. #include <gtest/gtest.h>
  38. #include <ros/ros.h>
  39. #include <costmap_2d/costmap_2d_ros.h>
  40. #include <tf2_geometry_msgs/tf2_geometry_msgs.h>
  41. #include <tf2_ros/transform_listener.h>
  42. using namespace costmap_2d;
  43. tf2_ros::TransformListener* tfl_;
  44. tf2_ros::Buffer* tf_;
  45. TEST( Costmap2DROS, unpadded_footprint_from_string_param )
  46. {
  47. Costmap2DROS cm( "unpadded/string", *tf_ );
  48. std::vector<geometry_msgs::Point> footprint = cm.getRobotFootprint();
  49. EXPECT_EQ( 3, footprint.size() );
  50. EXPECT_EQ( 1.0f, footprint[ 0 ].x );
  51. EXPECT_EQ( 1.0f, footprint[ 0 ].y );
  52. EXPECT_EQ( 0.0f, footprint[ 0 ].z );
  53. EXPECT_EQ( -1.0f, footprint[ 1 ].x );
  54. EXPECT_EQ( 1.0f, footprint[ 1 ].y );
  55. EXPECT_EQ( 0.0f, footprint[ 1 ].z );
  56. EXPECT_EQ( -1.0f, footprint[ 2 ].x );
  57. EXPECT_EQ( -1.0f, footprint[ 2 ].y );
  58. EXPECT_EQ( 0.0f, footprint[ 2 ].z );
  59. }
  60. TEST( Costmap2DROS, padded_footprint_from_string_param )
  61. {
  62. Costmap2DROS cm( "padded/string", *tf_ );
  63. std::vector<geometry_msgs::Point> footprint = cm.getRobotFootprint();
  64. EXPECT_EQ( 3, footprint.size() );
  65. EXPECT_EQ( 1.5f, footprint[ 0 ].x );
  66. EXPECT_EQ( 1.5f, footprint[ 0 ].y );
  67. EXPECT_EQ( 0.0f, footprint[ 0 ].z );
  68. EXPECT_EQ( -1.5f, footprint[ 1 ].x );
  69. EXPECT_EQ( 1.5f, footprint[ 1 ].y );
  70. EXPECT_EQ( 0.0f, footprint[ 1 ].z );
  71. EXPECT_EQ( -1.5f, footprint[ 2 ].x );
  72. EXPECT_EQ( -1.5f, footprint[ 2 ].y );
  73. EXPECT_EQ( 0.0f, footprint[ 2 ].z );
  74. }
  75. TEST( Costmap2DROS, radius_param )
  76. {
  77. Costmap2DROS cm( "radius/sub", *tf_ );
  78. std::vector<geometry_msgs::Point> footprint = cm.getRobotFootprint();
  79. // Circular robot has 16-point footprint auto-generated.
  80. EXPECT_EQ( 16, footprint.size() );
  81. // Check the first point
  82. EXPECT_EQ( 10.0f, footprint[ 0 ].x );
  83. EXPECT_EQ( 0.0f, footprint[ 0 ].y );
  84. EXPECT_EQ( 0.0f, footprint[ 0 ].z );
  85. // Check the 4th point, which should be 90 degrees around the circle from the first.
  86. EXPECT_NEAR( 0.0f, footprint[ 4 ].x, 0.0001 );
  87. EXPECT_NEAR( 10.0f, footprint[ 4 ].y, 0.0001 );
  88. EXPECT_EQ( 0.0f, footprint[ 4 ].z );
  89. }
  90. TEST( Costmap2DROS, footprint_from_xmlrpc_param )
  91. {
  92. Costmap2DROS cm( "xmlrpc", *tf_ );
  93. std::vector<geometry_msgs::Point> footprint = cm.getRobotFootprint();
  94. EXPECT_EQ( 4, footprint.size() );
  95. EXPECT_EQ( 0.1f, footprint[ 0 ].x );
  96. EXPECT_EQ( 0.1f, footprint[ 0 ].y );
  97. EXPECT_EQ( 0.0f, footprint[ 0 ].z );
  98. EXPECT_EQ( -0.1f, footprint[ 1 ].x );
  99. EXPECT_EQ( 0.1f, footprint[ 1 ].y );
  100. EXPECT_EQ( 0.0f, footprint[ 1 ].z );
  101. EXPECT_EQ( -0.1f, footprint[ 2 ].x );
  102. EXPECT_EQ( -0.1f, footprint[ 2 ].y );
  103. EXPECT_EQ( 0.0f, footprint[ 2 ].z );
  104. EXPECT_EQ( 0.1f, footprint[ 3 ].x );
  105. EXPECT_EQ( -0.1f, footprint[ 3 ].y );
  106. EXPECT_EQ( 0.0f, footprint[ 3 ].z );
  107. }
  108. TEST( Costmap2DROS, footprint_from_same_level_param )
  109. {
  110. Costmap2DROS cm( "same_level", *tf_ );
  111. std::vector<geometry_msgs::Point> footprint = cm.getRobotFootprint();
  112. EXPECT_EQ( 3, footprint.size() );
  113. EXPECT_EQ( 1.0f, footprint[ 0 ].x );
  114. EXPECT_EQ( 2.0f, footprint[ 0 ].y );
  115. EXPECT_EQ( 0.0f, footprint[ 0 ].z );
  116. EXPECT_EQ( 3.0f, footprint[ 1 ].x );
  117. EXPECT_EQ( 4.0f, footprint[ 1 ].y );
  118. EXPECT_EQ( 0.0f, footprint[ 1 ].z );
  119. EXPECT_EQ( 5.0f, footprint[ 2 ].x );
  120. EXPECT_EQ( 6.0f, footprint[ 2 ].y );
  121. EXPECT_EQ( 0.0f, footprint[ 2 ].z );
  122. }
  123. TEST( Costmap2DROS, footprint_from_xmlrpc_param_failure )
  124. {
  125. ASSERT_ANY_THROW( Costmap2DROS cm( "xmlrpc_fail", *tf_ ));
  126. }
  127. TEST( Costmap2DROS, footprint_empty )
  128. {
  129. Costmap2DROS cm( "empty", *tf_ );
  130. std::vector<geometry_msgs::Point> footprint = cm.getRobotFootprint();
  131. // With no specification of footprint or radius, defaults to 0.46 meter radius plus 0.01 meter padding.
  132. EXPECT_EQ( 16, footprint.size() );
  133. EXPECT_NEAR( 0.47f, footprint[ 0 ].x, 0.0001 );
  134. EXPECT_NEAR( 0.0f, footprint[ 0 ].y, 0.0001 );
  135. EXPECT_EQ( 0.0f, footprint[ 0 ].z );
  136. }
  137. int main(int argc, char** argv)
  138. {
  139. ros::init(argc, argv, "footprint_tests_node");
  140. tf_ = new tf2_ros::Buffer( ros::Duration( 10 ));
  141. tfl_ = new tf2_ros::TransformListener(*tf_);
  142. // This empty transform is added to satisfy the constructor of
  143. // Costmap2DROS, which waits for the transform from map to base_link
  144. // to become available.
  145. geometry_msgs::TransformStamped base_rel_map;
  146. base_rel_map.transform = tf2::toMsg(tf2::Transform::getIdentity());
  147. base_rel_map.child_frame_id = "base_link";
  148. base_rel_map.header.frame_id = "map";
  149. base_rel_map.header.stamp = ros::Time::now();
  150. tf_->setTransform( base_rel_map, "footprint_tests" );
  151. testing::InitGoogleTest(&argc, argv);
  152. return RUN_ALL_TESTS();
  153. }