Go to the documentation of this file.
40 #include <gtest/gtest.h>
73 TEST(costmap, testRaytracing){
90 ASSERT_EQ(lethal_count, 21);
96 TEST(costmap, testRaytracing2){
113 ASSERT_EQ(obs_before, 20);
128 ASSERT_EQ(obs_after, obs_before + 1);
144 ASSERT_EQ(with_static, obs_after);
152 TEST(costmap, testWaveInterference){
203 TEST(costmap, testDynamicObstacles){
229 TEST(costmap, testMultipleAdditions){
247 int main(
int argc,
char** argv){
249 testing::InitGoogleTest(&argc, argv);
250 return RUN_ALL_TESTS();
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
void addObservation(costmap_2d::ObstacleLayer *olayer, double x, double y, double z=0.0, double ox=0.0, double oy=0.0, double oz=MAX_Z)
void addStaticLayer(costmap_2d::LayeredCostmap &layers, tf2_ros::Buffer &tf)
static const unsigned char NO_INFORMATION
void resizeMap(unsigned int size_x, unsigned int size_y, double resolution, double origin_x, double origin_y, bool size_locked=false)
A 2D costmap provides a mapping between points in the world and their associated "costs".
void setCost(unsigned int mx, unsigned int my, unsigned char cost)
Set the cost of a cell in the costmap.
costmap_2d::ObstacleLayer * addObstacleLayer(costmap_2d::LayeredCostmap &layers, tf2_ros::Buffer &tf)
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
static const unsigned char LETHAL_OBSTACLE
int main(int argc, char **argv)
TEST(costmap, testRaytracing)
void updateMap(double robot_x, double robot_y, double robot_yaw)
Update the underlying costmap with new data. If you want to update the map outside of the update loop...
Instantiates different layer plugins and aggregates them into one score.
static const unsigned char FREE_SPACE
unsigned int countValues(costmap_2d::Costmap2D &costmap, unsigned char value, bool equal=true)
costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:17