Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix costmap publisher test #3679

Merged
merged 5 commits into from
Jul 6, 2023
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
13 changes: 7 additions & 6 deletions nav2_costmap_2d/test/integration/test_costmap_2d_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -117,7 +117,7 @@ class LayerSubscriber
protected:
void layerCallback(const nav2_msgs::msg::Costmap::SharedPtr layer)
{
if (!callback_hit_) {
if (!callback_hit_ && (layer->data.size() == 100)) {
layer_promise_.set_value(layer);
callback_hit_ = true;
}
Expand Down Expand Up @@ -157,23 +157,24 @@ TEST_F(CostmapRosTestFixture, costmap_pub_test)
{
auto future = layer_subscriber_->layer_promise_.get_future();
auto status = future.wait_for(std::chrono::seconds(5));
EXPECT_TRUE(status == std::future_status::ready);
ASSERT_TRUE(status == std::future_status::ready);

auto costmap_raw = future.get();

// Check first 20 cells of the 10by10 map
ASSERT_TRUE(costmap_raw->data.size() == 100);
unsigned int i = 0;
for (; i < 7; ++i) {
EXPECT_EQ(costmap_raw->data[i], nav2_costmap_2d::FREE_SPACE);
EXPECT_EQ(costmap_raw->data.at(i), nav2_costmap_2d::FREE_SPACE);
}
for (; i < 10; ++i) {
EXPECT_EQ(costmap_raw->data[i], nav2_costmap_2d::LETHAL_OBSTACLE);
EXPECT_EQ(costmap_raw->data.at(i), nav2_costmap_2d::LETHAL_OBSTACLE);
}
for (; i < 17; ++i) {
EXPECT_EQ(costmap_raw->data[i], nav2_costmap_2d::FREE_SPACE);
EXPECT_EQ(costmap_raw->data.at(i), nav2_costmap_2d::FREE_SPACE);
}
for (; i < 20; ++i) {
EXPECT_EQ(costmap_raw->data[i], nav2_costmap_2d::LETHAL_OBSTACLE);
EXPECT_EQ(costmap_raw->data.at(i), nav2_costmap_2d::LETHAL_OBSTACLE);
}

SUCCEED();
Expand Down