@@ -117,7 +117,7 @@ class LayerSubscriber
117117protected:
118118 void layerCallback (const nav2_msgs::msg::Costmap::SharedPtr layer)
119119 {
120- if (!callback_hit_) {
120+ if (!callback_hit_ && (layer-> data . size () == 100 ) ) {
121121 layer_promise_.set_value (layer);
122122 callback_hit_ = true ;
123123 }
@@ -157,23 +157,24 @@ TEST_F(CostmapRosTestFixture, costmap_pub_test)
157157{
158158 auto future = layer_subscriber_->layer_promise_ .get_future ();
159159 auto status = future.wait_for (std::chrono::seconds (5 ));
160- EXPECT_TRUE (status == std::future_status::ready);
160+ ASSERT_TRUE (status == std::future_status::ready);
161161
162162 auto costmap_raw = future.get ();
163163
164164 // Check first 20 cells of the 10by10 map
165+ ASSERT_TRUE (costmap_raw->data .size () == 100 );
165166 unsigned int i = 0 ;
166167 for (; i < 7 ; ++i) {
167- EXPECT_EQ (costmap_raw->data [i] , nav2_costmap_2d::FREE_SPACE);
168+ EXPECT_EQ (costmap_raw->data . at (i) , nav2_costmap_2d::FREE_SPACE);
168169 }
169170 for (; i < 10 ; ++i) {
170- EXPECT_EQ (costmap_raw->data [i] , nav2_costmap_2d::LETHAL_OBSTACLE);
171+ EXPECT_EQ (costmap_raw->data . at (i) , nav2_costmap_2d::LETHAL_OBSTACLE);
171172 }
172173 for (; i < 17 ; ++i) {
173- EXPECT_EQ (costmap_raw->data [i] , nav2_costmap_2d::FREE_SPACE);
174+ EXPECT_EQ (costmap_raw->data . at (i) , nav2_costmap_2d::FREE_SPACE);
174175 }
175176 for (; i < 20 ; ++i) {
176- EXPECT_EQ (costmap_raw->data [i] , nav2_costmap_2d::LETHAL_OBSTACLE);
177+ EXPECT_EQ (costmap_raw->data . at (i) , nav2_costmap_2d::LETHAL_OBSTACLE);
177178 }
178179
179180 SUCCEED ();
0 commit comments