Skip to content

Commit b4123c3

Browse files
committed
adding unit test
1 parent 0d70d7c commit b4123c3

File tree

3 files changed

+84
-5
lines changed

3 files changed

+84
-5
lines changed

nav2_util/include/nav2_util/base_footprint_publisher.hpp

Lines changed: 8 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@
1616
#define NAV2_UTIL__BASE_FOOTPRINT_PUBLISHER_HPP_
1717

1818
#include <string>
19+
#include <memory>
1920

2021
#include "rclcpp/rclcpp.hpp"
2122
#include "tf2_msgs/msg/tf_message.hpp"
@@ -24,6 +25,7 @@
2425
#include "tf2_ros/transform_listener.h"
2526
#include "tf2_ros/transform_broadcaster.h"
2627
#include "tf2_ros/buffer.h"
28+
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
2729
#include "tf2/utils.h"
2830

2931
namespace nav2_util
@@ -36,6 +38,7 @@ namespace nav2_util
3638
*/
3739
class BaseFootprintPublisherListener : public tf2_ros::TransformListener
3840
{
41+
public:
3942
BaseFootprintPublisherListener(tf2::BufferCore & buffer, bool spin_thread, rclcpp::Node & node)
4043
: tf2_ros::TransformListener(buffer, spin_thread)
4144
{
@@ -72,7 +75,7 @@ class BaseFootprintPublisherListener : public tf2_ros::TransformListener
7275
transform.transform.translation.z = 0.0;
7376

7477
// Remove Roll and Pitch
75-
tf::Quaternion q;
78+
tf2::Quaternion q;
7679
q.setRPY(0, 0, tf2::getYaw(t.transform.rotation));
7780
q.normalize();
7881
transform.transform.rotation.x = q.x();
@@ -103,17 +106,17 @@ class BaseFootprintPublisher : public rclcpp::Node
103106
/**
104107
* @brief A constructor
105108
*/
106-
BaseFootprintPublisher(const rclcpp::NodeOptions & options = rclcpp::NodeOptions())
109+
explicit BaseFootprintPublisher(const rclcpp::NodeOptions & options = rclcpp::NodeOptions())
107110
: Node("base_footprint_publisher", options)
108111
{
109112
RCLCPP_INFO(get_logger(), "Creating base footprint publisher");
110113
tf_buffer_ = std::make_shared<tf2_ros::Buffer>(get_clock());
111114
auto timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(
112115
get_node_base_interface(),
113-
get_node_timers_interface(),
114-
callback_group_);
116+
get_node_timers_interface());
115117
tf_buffer_->setCreateTimerInterface(timer_interface);
116-
listener_publisher_ = std::make_shared<BaseFootprintPublisherListener>(*tf_buffer_, *this);
118+
listener_publisher_ = std::make_shared<BaseFootprintPublisherListener>(
119+
*tf_buffer_, true, *this);
117120
}
118121

119122
protected:

nav2_util/test/CMakeLists.txt

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -41,3 +41,7 @@ target_link_libraries(test_odometry_utils ${library_name})
4141
ament_add_gtest(test_robot_utils test_robot_utils.cpp)
4242
ament_target_dependencies(test_robot_utils geometry_msgs)
4343
target_link_libraries(test_robot_utils ${library_name})
44+
45+
ament_add_gtest(test_base_footprint_publisher test_base_footprint_publisher.cpp)
46+
ament_target_dependencies(test_base_footprint_publisher geometry_msgs)
47+
target_link_libraries(test_base_footprint_publisher ${library_name})
Lines changed: 72 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,72 @@
1+
// Copyright (c) 2023 Open Navigation LLC
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#include <string>
16+
#include <memory>
17+
18+
#include "nav2_util/base_footprint_publisher.hpp"
19+
#include "gtest/gtest.h"
20+
#include "tf2/exceptions.h"
21+
22+
class RclCppFixture
23+
{
24+
public:
25+
RclCppFixture() {rclcpp::init(0, nullptr);}
26+
~RclCppFixture() {rclcpp::shutdown();}
27+
};
28+
RclCppFixture g_rclcppfixture;
29+
30+
TEST(TestBaseFootprintPublisher, TestBaseFootprintPublisher)
31+
{
32+
auto node = std::make_shared<nav2_util::BaseFootprintPublisher>();
33+
rclcpp::spin_some(node->get_node_base_interface());
34+
35+
auto tf_broadcaster = std::make_shared<tf2_ros::TransformBroadcaster>(node);
36+
auto buffer = std::make_shared<tf2_ros::Buffer>(node->get_clock());
37+
auto timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(
38+
node->get_node_base_interface(),
39+
node->get_node_timers_interface());
40+
buffer->setCreateTimerInterface(timer_interface);
41+
auto listener = std::make_shared<tf2_ros::TransformListener>(*buffer, true);
42+
43+
std::string base_link = "base_link";
44+
std::string base_footprint = "base_footprint";
45+
46+
// Publish something to TF, should fail, doesn't exist
47+
geometry_msgs::msg::TransformStamped transform;
48+
transform.header.stamp = node->now();
49+
transform.header.frame_id = "test1_1";
50+
transform.child_frame_id = "test1";
51+
tf_broadcaster->sendTransform(transform);
52+
rclcpp::spin_some(node->get_node_base_interface());
53+
EXPECT_THROW(
54+
buffer->lookupTransform(base_link, base_footprint, tf2::TimePointZero),
55+
tf2::TransformException);
56+
57+
// This is valid, should work now and communicate the Z-removed info
58+
transform.header.stamp = node->now();
59+
transform.header.frame_id = "odom";
60+
transform.child_frame_id = "base_link";
61+
transform.transform.translation.x = 1.0;
62+
transform.transform.translation.y = 1.0;
63+
transform.transform.translation.z = 1.0;
64+
tf_broadcaster->sendTransform(transform);
65+
rclcpp::Rate r(1.0);
66+
r.sleep();
67+
rclcpp::spin_some(node->get_node_base_interface());
68+
auto t = buffer->lookupTransform(base_link, base_footprint, tf2::TimePointZero);
69+
EXPECT_EQ(t.transform.translation.x, 1.0);
70+
EXPECT_EQ(t.transform.translation.y, 1.0);
71+
EXPECT_EQ(t.transform.translation.z, 0.0);
72+
}

0 commit comments

Comments
 (0)