test/rostests/from_ros_costmaps/from_ros_costmaps.cpp
Go to the documentation of this file.
1 
4 /*****************************************************************************
5 ** Includes
6 *****************************************************************************/
7 
9 #include <gtest/gtest.h>
10 #include <iostream>
11 #include <string>
12 
13 #include "../../../../include/cost_map_demos/from_ros_costmaps.hpp"
14 
15 /*****************************************************************************
16 ** Tests
17 *****************************************************************************/
18 
19 TEST(Costmap2DROS, full_window) {
20  std::cout << std::endl;
21  ROS_INFO("***********************************************************");
22  ROS_INFO(" Copy Full Window");
23  ROS_INFO("***********************************************************");
24  // MAKE SURE THIS STAY IN SYNC WITH src/applications/from_ros_costmaps.cpp!
25  // preparation
26  std::string layer_name = "obstacle_costs";
27  cost_map_demos::ROSCostmapServer ros_costmap_5x5("five_by_five", "base_link_5x5", cost_map::Position(0.0, 0.0), 5.0, 5.0);
28  cost_map::CostMap cost_map_5x5, cost_map_4x4;
29  cost_map::fromCostmap2DROS(*(ros_costmap_5x5.getROSCostmap()), layer_name, cost_map_5x5);
30  // assert map properties
31  ASSERT_EQ(cost_map_5x5.getFrameId(), ros_costmap_5x5.getROSCostmap()->getGlobalFrameID());
32  ASSERT_EQ(cost_map_5x5.getLength().x(),
33  ros_costmap_5x5.getROSCostmap()->getCostmap()->getSizeInCellsX()*ros_costmap_5x5.getROSCostmap()->getCostmap()->getResolution()
34  );
35  ASSERT_EQ(cost_map_5x5.getLength().y(),
36  ros_costmap_5x5.getROSCostmap()->getCostmap()->getSizeInCellsY()*ros_costmap_5x5.getROSCostmap()->getCostmap()->getResolution()
37  );
38  ASSERT_EQ(cost_map_5x5.getSize()[0], ros_costmap_5x5.getROSCostmap()->getCostmap()->getSizeInCellsX());
39  ASSERT_EQ(cost_map_5x5.getSize()[1], ros_costmap_5x5.getROSCostmap()->getCostmap()->getSizeInCellsY());
40  cost_map::Length position = cost_map_5x5.getPosition() - 0.5 * cost_map_5x5.getLength().matrix();
41  ASSERT_EQ(position.x(), ros_costmap_5x5.getROSCostmap()->getCostmap()->getOriginX());
42  ASSERT_EQ(position.y(), ros_costmap_5x5.getROSCostmap()->getCostmap()->getOriginY());
43  // assert map data
44 // for ( unsigned int i = 0; i < 5; ++i ) {
45 // for ( unsigned int j = 0; j < 5; ++j ) {
46 // std::cout << static_cast<int>(ros_costmap_5x5.getROSCostmap()->getCostmap()->getCost(i,j)) << " ";
47 // }
48 // std::cout << std::endl;
49 // }
50 // for ( unsigned int i = 0; i < 5; ++i ) {
51 // for ( unsigned int j = 0; j < 5; ++j ) {
52 // std::cout << static_cast<int>(cost_map_5x5.at(layer_name, cost_map::Index(i,j))) << " ";
53 // }
54 // std::cout << std::endl;
55 // }
56  // TODO a function which does the index conversion
57  ASSERT_EQ(cost_map_5x5.at(layer_name, cost_map::Index(1,9)), ros_costmap_5x5.getROSCostmap()->getCostmap()->getCost(8,0));
58  std::cout << std::endl;
59 }
60 
61 TEST(Costmap2DROS, cost_map_centres) {
62  std::cout << std::endl;
63  ROS_INFO("***********************************************************");
64  ROS_INFO(" Check Subwindow Centres");
65  ROS_INFO("***********************************************************");
66  ROS_INFO("Subwindows are centred as closely as possible to the robot");
67  ROS_INFO("pose, though not exactly. They still need to align with");
68  ROS_INFO("the underlying ros costmap so that they don't introduce a");
69  ROS_INFO("new kind of error. As a result, the centre is shifted from");
70  ROS_INFO("the robot pose to the nearest appropriate point which aligns");
71  ROS_INFO("the new cost map exactly on top of the original ros costmap.");
72  std::cout << std::endl;
73  std::string layer_name = "obstacle_costs";
74  cost_map_demos::ROSCostmapServer ros_costmap_5x5_3x3_offset("five_by_five_three_by_three_offset", "base_link_5x5_3x3_offset", cost_map::Position(-6.0, 0.0), 5.0, 5.0);
75  cost_map_demos::ROSCostmapServer ros_costmap_5x5_3x3_centre("five_by_five_three_by_three_centre", "base_link_5x5_3x3_centre", cost_map::Position(-6.0, -6.0), 5.0, 5.0);
76  cost_map_demos::ROSCostmapServer ros_costmap_5x5_2_5x2_5_offset("five_by_five_twohalf_by_twohalf_offset", "base_link_5x5_2_5x2_5_offset", cost_map::Position(-12.0, 0.0), 5.0, 5.0);
77  cost_map::CostMap cost_map_5x5_3x3_offset, cost_map_5x5_3x3_centre, cost_map_5x5_2_5x2_5_offset;
78  cost_map::Length geometry_3x3(3.0, 3.0);
79  cost_map::fromCostmap2DROSAtRobotPose(*(ros_costmap_5x5_3x3_offset.getROSCostmap()), geometry_3x3, layer_name, cost_map_5x5_3x3_offset);
80  cost_map::fromCostmap2DROSAtRobotPose(*(ros_costmap_5x5_3x3_centre.getROSCostmap()), geometry_3x3, layer_name, cost_map_5x5_3x3_centre);
81  cost_map::Length geometry_2_5x2_5(2.5, 2.5);
82  cost_map::fromCostmap2DROSAtRobotPose(*(ros_costmap_5x5_2_5x2_5_offset.getROSCostmap()), geometry_2_5x2_5, layer_name, cost_map_5x5_2_5x2_5_offset);
83  ROS_INFO_STREAM(" cost_map_5x5_3x3_offset : " << cost_map_5x5_3x3_offset.getPosition().transpose());
84  ROS_INFO_STREAM(" cost_map_5x5_3x3_offset : " << cost_map_5x5_3x3_centre.getPosition().transpose());
85  ROS_INFO_STREAM(" cost_map_5x5_3x3_offset : " << cost_map_5x5_2_5x2_5_offset.getPosition().transpose());
86  ASSERT_EQ(-3.5, cost_map_5x5_3x3_offset.getPosition().x());
87  ASSERT_EQ(2.5, cost_map_5x5_3x3_offset.getPosition().y());
88  ASSERT_EQ(-3.5, cost_map_5x5_3x3_centre.getPosition().x());
89  ASSERT_EQ(-3.5, cost_map_5x5_3x3_centre.getPosition().y());
90  ASSERT_EQ(-9.75, cost_map_5x5_2_5x2_5_offset.getPosition().x());
91  ASSERT_EQ(2.25, cost_map_5x5_2_5x2_5_offset.getPosition().y());
92  std::cout << std::endl;
93 }
94 
95 /*****************************************************************************
96 ** Main program
97 *****************************************************************************/
98 
99 int main(int argc, char **argv) {
100 
101  ros::init(argc, argv, "test_from_ros_costmaps");
102 
105 
106  testing::InitGoogleTest(&argc,argv);
107  int result = RUN_ALL_TESTS();
108  broadcaster.shutdown();
109  return result;
110 }
111 
112 
const Length & getLength() const
int main(int argc, char **argv)
DataType & at(const std::string &layer, const Index &index)
const Size & getSize() const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
const std::string & getFrameId() const
#define ROS_INFO(...)
Broadcast a set of transforms useful for various demos.
Definition: utilities.hpp:35
bool getPosition(const Index &index, Position &position) const
grid_map::Index Index
TEST(Costmap2DROS, full_window)
bool fromCostmap2DROS(costmap_2d::Costmap2DROS &ros_costmap, const std::string &layer_name, cost_map::CostMap &cost_map)
#define ROS_INFO_STREAM(args)
grid_map::Position Position
void broadcastCostmap2DROSTestSuiteTransforms(TransformBroadcaster &broadcaster)
grid_map::Length Length
bool fromCostmap2DROSAtRobotPose(costmap_2d::Costmap2DROS &ros_costmap, const cost_map::Length &geometry, const std::string &layer_name, cost_map::CostMap &cost_map)


cost_map_demos
Author(s): Daniel Stonier
autogenerated on Mon Jun 10 2019 13:04:00