Skip to content

Commit 0d70d7c

Browse files
committed
adding base footprint publisher to nav2_util
1 parent 7274811 commit 0d70d7c

File tree

3 files changed

+158
-0
lines changed

3 files changed

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

nav2_util/src/CMakeLists.txt

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -28,6 +28,11 @@ add_executable(lifecycle_bringup
2828
)
2929
target_link_libraries(lifecycle_bringup ${library_name})
3030

31+
add_executable(base_footprint_publisher
32+
base_footprint_publisher.cpp
33+
)
34+
target_link_libraries(base_footprint_publisher ${library_name})
35+
3136
find_package(Boost REQUIRED COMPONENTS program_options)
3237

3338
install(TARGETS
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+
}

0 commit comments

Comments
 (0)