unload_test.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2018, Locus Robotics
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 #include <gtest/gtest.h>
36 
37 
38 TEST(LocalPlannerAdapter, unload_local_planner)
39 {
41  tf.setUsingDedicatedThread(true);
42 
43  // This empty transform is added to satisfy the constructor of
44  // Costmap2DROS, which waits for the transform from map to base_link
45  // to become available.
46  geometry_msgs::TransformStamped base_rel_map;
47  base_rel_map.child_frame_id = "/base_link";
48  base_rel_map.header.frame_id = "/map";
49  base_rel_map.transform.rotation.w = 1.0;
50  tf.setTransform(base_rel_map, "unload", true);
51 
53 
54  costmap_2d::Costmap2DROS costmap_ros("local_costmap", tf);
55  lpa->initialize("lpa", &tf, &costmap_ros);
56 
57  delete lpa;
58 
59  // Simple test to make sure costmap hasn't been deleted
60  EXPECT_EQ("map", costmap_ros.getGlobalFrameID());
61 }
62 
63 
64 int main(int argc, char** argv)
65 {
66  ros::init(argc, argv, "unload_test");
67  testing::InitGoogleTest(&argc, argv);
68  return RUN_ALL_TESTS();
69 }
TEST
TEST(LocalPlannerAdapter, unload_local_planner)
Definition: unload_test.cpp:38
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
nav_core_adapter::LocalPlannerAdapter::initialize
void initialize(std::string name, tf2_ros::Buffer *tf, costmap_2d::Costmap2DROS *costmap_ros) override
Load the nav_core2 local planner and initialize it.
Definition: local_planner_adapter.cpp:57
nav_core_adapter::LocalPlannerAdapter
used for employing a nav_core2 local planner (such as dwb) as a nav_core plugin, like in move_base.
Definition: local_planner_adapter.h:54
tf2_ros::Buffer
main
int main(int argc, char **argv)
Definition: unload_test.cpp:64
tf
local_planner_adapter.h
costmap_2d::Costmap2DROS::getGlobalFrameID
const std::string & getGlobalFrameID() const noexcept
costmap_2d::Costmap2DROS


nav_core_adapter
Author(s):
autogenerated on Sun May 18 2025 02:47:37