Skip to content

Commit c58e235

Browse files
SteveMacenskiMarc-Morcos
authored andcommitted
Revert "Revert "adding base footprint publisher to nav2_util (ros-navigation#3860)" (ros-navigation#3994)" (ros-navigation#3995)
This reverts commit ef85df2.
1 parent 4b82ae5 commit c58e235

File tree

3 files changed

+228
-0
lines changed

3 files changed

+228
-0
lines changed
Lines changed: 129 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,129 @@
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+
#ifndef NAV2_UTIL__BASE_FOOTPRINT_PUBLISHER_HPP_
16+
#define NAV2_UTIL__BASE_FOOTPRINT_PUBLISHER_HPP_
17+
18+
#include <string>
19+
#include <memory>
20+
21+
#include "rclcpp/rclcpp.hpp"
22+
#include "tf2_msgs/msg/tf_message.hpp"
23+
#include "geometry_msgs/msg/transform_stamped.hpp"
24+
#include "tf2_ros/create_timer_ros.h"
25+
#include "tf2_ros/transform_listener.h"
26+
#include "tf2_ros/transform_broadcaster.h"
27+
#include "tf2_ros/buffer.h"
28+
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
29+
#include "tf2/utils.h"
30+
31+
namespace nav2_util
32+
{
33+
34+
/**
35+
* @brief A TF2 listener that overrides the subscription callback
36+
* to inject base footprint publisher removing Z, Pitch, and Roll for
37+
* 3D state estimation but desiring a 2D frame for navigation, visualization, or other reasons
38+
*/
39+
class BaseFootprintPublisherListener : public tf2_ros::TransformListener
40+
{
41+
public:
42+
BaseFootprintPublisherListener(tf2::BufferCore & buffer, bool spin_thread, rclcpp::Node & node)
43+
: tf2_ros::TransformListener(buffer, spin_thread)
44+
{
45+
node.declare_parameter(
46+
"base_link_frame", rclcpp::ParameterValue(std::string("base_link")));
47+
node.declare_parameter(
48+
"base_footprint_frame", rclcpp::ParameterValue(std::string("base_footprint")));
49+
base_link_frame_ = node.get_parameter("base_link_frame").as_string();
50+
base_footprint_frame_ = node.get_parameter("base_footprint_frame").as_string();
51+
tf_broadcaster_ = std::make_shared<tf2_ros::TransformBroadcaster>(node);
52+
}
53+
54+
/**
55+
* @brief Overrides TF2 subscription callback to inject base footprint publisher
56+
*/
57+
void subscription_callback(tf2_msgs::msg::TFMessage::ConstSharedPtr msg, bool is_static) override
58+
{
59+
TransformListener::subscription_callback(msg, is_static);
60+
61+
if (is_static) {
62+
return;
63+
}
64+
65+
for (unsigned int i = 0; i != msg->transforms.size(); i++) {
66+
auto & t = msg->transforms[i];
67+
if (t.child_frame_id == base_link_frame_) {
68+
geometry_msgs::msg::TransformStamped transform;
69+
transform.header.stamp = t.header.stamp;
70+
transform.header.frame_id = base_link_frame_;
71+
transform.child_frame_id = base_footprint_frame_;
72+
73+
// Project to Z-zero
74+
transform.transform.translation = t.transform.translation;
75+
transform.transform.translation.z = 0.0;
76+
77+
// Remove Roll and Pitch
78+
tf2::Quaternion q;
79+
q.setRPY(0, 0, tf2::getYaw(t.transform.rotation));
80+
q.normalize();
81+
transform.transform.rotation.x = q.x();
82+
transform.transform.rotation.y = q.y();
83+
transform.transform.rotation.z = q.z();
84+
transform.transform.rotation.w = q.w();
85+
86+
tf_broadcaster_->sendTransform(transform);
87+
return;
88+
}
89+
}
90+
}
91+
92+
protected:
93+
std::shared_ptr<tf2_ros::TransformBroadcaster> tf_broadcaster_;
94+
std::string base_link_frame_, base_footprint_frame_;
95+
};
96+
97+
/**
98+
* @class nav2_util::BaseFootprintPublisher
99+
* @brief Republishes the ``base_link`` frame as ``base_footprint``
100+
* stripping away the Z, Roll, and Pitch of the full 3D state to provide
101+
* a 2D projection for navigation when state estimation is full 3D
102+
*/
103+
class BaseFootprintPublisher : public rclcpp::Node
104+
{
105+
public:
106+
/**
107+
* @brief A constructor
108+
*/
109+
explicit BaseFootprintPublisher(const rclcpp::NodeOptions & options = rclcpp::NodeOptions())
110+
: Node("base_footprint_publisher", options)
111+
{
112+
RCLCPP_INFO(get_logger(), "Creating base footprint publisher");
113+
tf_buffer_ = std::make_shared<tf2_ros::Buffer>(get_clock());
114+
auto timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(
115+
get_node_base_interface(),
116+
get_node_timers_interface());
117+
tf_buffer_->setCreateTimerInterface(timer_interface);
118+
listener_publisher_ = std::make_shared<BaseFootprintPublisherListener>(
119+
*tf_buffer_, true, *this);
120+
}
121+
122+
protected:
123+
std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
124+
std::shared_ptr<BaseFootprintPublisherListener> listener_publisher_;
125+
};
126+
127+
} // end namespace nav2_util
128+
129+
#endif // NAV2_UTIL__BASE_FOOTPRINT_PUBLISHER_HPP_
Lines changed: 27 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,27 @@
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 <memory>
16+
17+
#include "nav2_util/base_footprint_publisher.hpp"
18+
19+
int main(int argc, char ** argv)
20+
{
21+
rclcpp::init(argc, argv);
22+
auto node = std::make_shared<nav2_util::BaseFootprintPublisher>();
23+
rclcpp::spin(node->get_node_base_interface());
24+
rclcpp::shutdown();
25+
26+
return 0;
27+
}
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)