them file test static_layer

This commit is contained in:
2025-11-07 17:44:42 +07:00
parent 79e706b798
commit 498b606e15
148 changed files with 6363 additions and 1599 deletions

132
test/coordinates_test.cpp Normal file
View File

@@ -0,0 +1,132 @@
/*
* Software License Agreement (BSD License)
*
* Copyright (c) 2019, Locus Robotics
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of the copyright holder nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/
// Tests ripped from https://github.com/locusrobotics/robot_navigation/blob/master/nav_grid/test/utest.cpp
#include <gtest/gtest.h>
#include <costmap_2d/costmap_2d.h>
using namespace costmap_2d;
TEST(CostmapCoordinates, easy_coordinates_test)
{
Costmap2D costmap(2, 3, 1.0, 0, 0);
double wx, wy;
costmap.mapToWorld(0u, 0u, wx, wy);
EXPECT_DOUBLE_EQ(wx, 0.5);
EXPECT_DOUBLE_EQ(wy, 0.5);
costmap.mapToWorld(1u, 2u, wx, wy);
EXPECT_DOUBLE_EQ(wx, 1.5);
EXPECT_DOUBLE_EQ(wy, 2.5);
unsigned int umx, umy;
int mx, my;
ASSERT_TRUE(costmap.worldToMap(wx, wy, umx, umy));
EXPECT_EQ(umx, 1);
EXPECT_EQ(umy, 2);
costmap.worldToMapNoBounds(wx, wy, mx, my);
EXPECT_EQ(mx, 1);
EXPECT_EQ(my, 2);
// Invalid Coordinate
wx = 2.5;
EXPECT_FALSE(costmap.worldToMap(wx, wy, umx, umy));
costmap.worldToMapEnforceBounds(wx, wy, mx, my);
EXPECT_EQ(mx, 1);
EXPECT_EQ(my, 2);
costmap.worldToMapNoBounds(wx, wy, mx, my);
EXPECT_EQ(mx, 2);
EXPECT_EQ(my, 2);
// Border Cases
EXPECT_TRUE(costmap.worldToMap(0.0, wy, umx, umy));
EXPECT_EQ(umx, 0);
EXPECT_TRUE(costmap.worldToMap(0.25, wy, umx, umy));
EXPECT_EQ(umx, 0);
EXPECT_TRUE(costmap.worldToMap(0.75, wy, umx, umy));
EXPECT_EQ(umx, 0);
EXPECT_TRUE(costmap.worldToMap(0.9999, wy, umx, umy));
EXPECT_EQ(umx, 0);
EXPECT_TRUE(costmap.worldToMap(1.0, wy, umx, umy));
EXPECT_EQ(umx, 1);
EXPECT_TRUE(costmap.worldToMap(1.25, wy, umx, umy));
EXPECT_EQ(umx, 1);
EXPECT_TRUE(costmap.worldToMap(1.75, wy, umx, umy));
EXPECT_EQ(umx, 1);
EXPECT_TRUE(costmap.worldToMap(1.9999, wy, umx, umy));
EXPECT_EQ(umx, 1);
EXPECT_FALSE(costmap.worldToMap(2.0, wy, umx, umy));
costmap.worldToMapEnforceBounds(2.0, wy, mx, my);
EXPECT_EQ(mx, 1);
}
TEST(CostmapCoordinates, hard_coordinates_test)
{
Costmap2D costmap(2, 3, 0.1, -0.2, 0.2);
double wx, wy;
costmap.mapToWorld(0, 0, wx, wy);
EXPECT_DOUBLE_EQ(wx, -0.15);
EXPECT_DOUBLE_EQ(wy, 0.25);
costmap.mapToWorld(1, 2, wx, wy);
EXPECT_DOUBLE_EQ(wx, -0.05);
EXPECT_DOUBLE_EQ(wy, 0.45);
unsigned int umx, umy;
int mx, my;
EXPECT_TRUE(costmap.worldToMap(wx, wy, umx, umy));
EXPECT_EQ(umx, 1);
EXPECT_EQ(umy, 2);
costmap.worldToMapNoBounds(wx, wy, mx, my);
EXPECT_EQ(mx, 1);
EXPECT_EQ(my, 2);
// Invalid Coordinate
wx = 2.5;
EXPECT_FALSE(costmap.worldToMap(wx, wy, umx, umy));
costmap.worldToMapEnforceBounds(wx, wy, mx, my);
EXPECT_EQ(mx, 1);
EXPECT_EQ(my, 2);
costmap.worldToMapNoBounds(wx, wy, mx, my);
EXPECT_EQ(mx, 27);
EXPECT_EQ(my, 2);
}
int main(int argc, char** argv)
{
testing::InitGoogleTest( &argc, argv );
return RUN_ALL_TESTS();
}

View File

@@ -0,0 +1,53 @@
#include <boost/dll/import.hpp>
#include <iostream>
#include <costmap_2d/costmap_layer.h>
#include <costmap_2d/layered_costmap.h>
#include <tf2/buffer_core.h>
#include <tf2/time.h>
#include "nav_msgs/OccupancyGrid.h"
using namespace costmap_2d;
int main(int argc, char* argv[]) {
// Fix 1: Use correct path to the library
auto creator = boost::dll::import_alias<costmap_2d::PluginCostmapLayerPtr()>(
"./costmap_2d/liblayers.so", "create_plugin", boost::dll::load_mode::append_decorations
);
costmap_2d::PluginCostmapLayerPtr plugin = creator();
std::cout << "Plugin created successfully" << std::endl;
// Fix 2: Initialize the plugin before calling activate()
// activate() calls onInitialize() which requires layered_costmap_ to be set
std::string global_frame = "map";
bool rolling_window = false;
bool track_unknown = true;
LayeredCostmap layered_costmap(global_frame, rolling_window, track_unknown);
// Fix 3: tf2::BufferCore constructor requires ros::Duration parameter (not tf2::Duration)
tf2::BufferCore tf_buffer;
// tf2::Duration cache_time(10.0); // 10 seconds cache time
// tf2::BufferCore tf_buffer(cache_time);
// Initialize the layer with required parameters
plugin->initialize(&layered_costmap, "static_layer", &tf_buffer);
std::cout << "Plugin initialized" << std::endl;
// Now it's safe to call activate()
// plugin->activate();
nav_msgs::OccupancyGrid grid;
grid.info.resolution = 0.05f;
grid.info.width = 2;
grid.info.height = 2;
grid.data.resize(grid.info.width * grid.info.height, -1);
grid.data[0] = 0; // Free cell
grid.data[1] = 100; // Occupied cell
grid.data[2] = 10; // Occupied cell
grid.data[3] = 0; // Free cell
plugin->incomingMap(grid);
std::cout << "Plugin activated successfully" << std::endl;
}