编写tf2监听程序 (c ++) [待校准@8673]
Goal目标: Learn了解如何使用tf2访问帧转换。 [待校准@8674]
Tutorial教程级别: Intermediate中级 [待校准@6713]
时间: 10分钟 [Alyssa@7452]
先决条件
本教程假设您已经完成了 tf2 broadcaster tutorial (C++) 。在之前的教程中,我们创建了一个 learning_tf2_cpp
包,在这里我们将继续工作。 [待校准@8677]
任务
1写入监听节点 [待校准@8678]
让我们先创建源文件。转到我们在上一教程中创建的 learning_tf2_cpp
包。在 src
目录中,通过输入以下命令下载示例侦听器代码: [待校准@8679]
wget https://raw.githubusercontent.com/ros/geometry_tutorials/ros2/turtle_tf2_cpp/src/turtle_tf2_listener.cpp
wget https://raw.githubusercontent.com/ros/geometry_tutorials/ros2/turtle_tf2_cpp/src/turtle_tf2_listener.cpp
在Windows命令行提示符下: [待校准@8363]
curl -sk https://raw.githubusercontent.com/ros/geometry_tutorials/ros2/turtle_tf2_cpp/src/turtle_tf2_listener.cpp -o turtle_tf2_listener.cpp
或者在powershell中: [待校准@8364]
curl https://raw.githubusercontent.com/ros/geometry_tutorials/ros2/turtle_tf2_cpp/src/turtle_tf2_listener.cpp -o turtle_tf2_listener.cpp
使用您喜欢的文本编辑器打开文件。 [待校准@8591]
#include <geometry_msgs/msg/transform_stamped.hpp>
#include <geometry_msgs/msg/twist.hpp>
#include <rclcpp/rclcpp.hpp>
#include <tf2/exceptions.h>
#include <tf2_ros/transform_listener.h>
#include <tf2_ros/buffer.h>
#include <turtlesim/srv/spawn.hpp>
#include <chrono>
#include <memory>
#include <string>
using std::placeholders::_1;
using namespace std::chrono_literals;
class FrameListener : public rclcpp::Node
{
public:
FrameListener()
: Node("turtle_tf2_frame_listener"),
turtle_spawning_service_ready_(false),
turtle_spawned_(false)
{
// Declare and acquire `target_frame` parameter
this->declare_parameter<std::string>("target_frame", "turtle1");
this->get_parameter("target_frame", target_frame_);
tf_buffer_ =
std::make_unique<tf2_ros::Buffer>(this->get_clock());
transform_listener_ =
std::make_shared<tf2_ros::TransformListener>(*tf_buffer_);
// Create a client to spawn a turtle
spawner_ =
this->create_client<turtlesim::srv::Spawn>("spawn");
// Create turtle2 velocity publisher
publisher_ =
this->create_publisher<geometry_msgs::msg::Twist>("turtle2/cmd_vel", 1);
// Call on_timer function every second
timer_ = this->create_wall_timer(
1s, std::bind(&FrameListener::on_timer, this));
}
private:
void on_timer()
{
// Store frame names in variables that will be used to
// compute transformations
std::string fromFrameRel = target_frame_.c_str();
std::string toFrameRel = "turtle2";
if (turtle_spawning_service_ready_) {
if (turtle_spawned_) {
geometry_msgs::msg::TransformStamped transformStamped;
// Look up for the transformation between target_frame and turtle2 frames
// and send velocity commands for turtle2 to reach target_frame
try {
transformStamped = tf_buffer_->lookupTransform(
toFrameRel, fromFrameRel,
tf2::TimePointZero);
} catch (tf2::TransformException & ex) {
RCLCPP_INFO(
this->get_logger(), "Could not transform %s to %s: %s",
toFrameRel.c_str(), fromFrameRel.c_str(), ex.what());
return;
}
geometry_msgs::msg::Twist msg;
static const double scaleRotationRate = 1.0;
msg.angular.z = scaleRotationRate * atan2(
transformStamped.transform.translation.y,
transformStamped.transform.translation.x);
static const double scaleForwardSpeed = 0.5;
msg.linear.x = scaleForwardSpeed * sqrt(
pow(transformStamped.transform.translation.x, 2) +
pow(transformStamped.transform.translation.y, 2));
publisher_->publish(msg);
} else {
RCLCPP_INFO(this->get_logger(), "Successfully spawned");
turtle_spawned_ = true;
}
} else {
// Check if the service is ready
if (spawner_->service_is_ready()) {
// Initialize request with turtle name and coordinates
// Note that x, y and theta are defined as floats in turtlesim/srv/Spawn
auto request = std::make_shared<turtlesim::srv::Spawn::Request>();
request->x = 4.0;
request->y = 2.0;
request->theta = 0.0;
request->name = "turtle2";
// Call request
using ServiceResponseFuture =
rclcpp::Client<turtlesim::srv::Spawn>::SharedFuture;
auto response_received_callback = [this](ServiceResponseFuture future) {
auto result = future.get();
if (strcmp(result->name.c_str(), "turtle2") == 0) {
turtle_spawning_service_ready_ = true;
} else {
RCLCPP_ERROR(this->get_logger(), "Service callback result mismatch");
}
};
auto result = spawner_->async_send_request(request, response_received_callback);
} else {
RCLCPP_INFO(this->get_logger(), "Service is not ready");
}
}
}
// Boolean values to store the information
// if the service for spawning turtle is available
bool turtle_spawning_service_ready_;
// if the turtle was successfully spawned
bool turtle_spawned_;
rclcpp::Client<turtlesim::srv::Spawn>::SharedPtr spawner_{nullptr};
rclcpp::TimerBase::SharedPtr timer_{nullptr};
rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr publisher_{nullptr};
std::shared_ptr<tf2_ros::TransformListener> transform_listener_{nullptr};
std::unique_ptr<tf2_ros::Buffer> tf_buffer_;
std::string target_frame_;
};
int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<FrameListener>());
rclcpp::shutdown();
return 0;
}
1.1检查代码 [待校准@8367]
要了解产卵海龟背后的服务是如何工作的,请参考 writing a simple service and client (C++) 教程。 [待校准@8680]
现在,让我们看一下与访问帧转换相关的代码。 tf2_ros
包含一个 TransformListener
头文件实现,使接收转换的任务更容易。 [待校准@8681]
#include <tf2_ros/transform_listener.h>
在这里,我们创建一个 TransformListener
对象。创建侦听器后,它开始通过导线接收tf2转换,并将其缓冲长达10秒。 [待校准@8682]
transform_listener_ =
std::make_shared<tf2_ros::TransformListener>(*tf_buffer_);
最后,我们向侦听器查询特定转换。我们使用以下参数调用 lookup_transform
方法: [待校准@8683]
目标帧 [待校准@8559]
源帧 [待校准@8561]
我们想要转换的时间 [待校准@8684]
提供 “tf2::TimePointZero()” 将为我们提供最新的可用转换。所有这些都包装在一个try-catch块中,以处理可能的异常。 [待校准@8685]
transformStamped = tf_buffer_->lookupTransform(
toFrameRel, fromFrameRel,
tf2::TimePointZero);
2构建和运行 [待校准@7729]
使用文本编辑器,打开调用 turtle_tf2_demo.launch.py
的launch文件,并在第一个 turtle1
广播器节点后添加以下行。此外,在文件开头包括 DeclareLaunchArgument
和 LaunchConfiguration
的进口: [待校准@8686]
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node
def generate_launch_description():
return LaunchDescription([
...,
DeclareLaunchArgument(
'target_frame', default_value='turtle1',
description='Target frame name.'
),
Node(
package='learning_tf2_cpp',
executable='turtle_tf2_broadcaster',
name='broadcaster2',
parameters=[
{'turtlename': 'turtle2'}
]
),
Node(
package='learning_tf2_cpp',
executable='turtle_tf2_listener',
name='listener',
parameters=[
{'target_frame': LaunchConfiguration('target_frame')}
]
),
])
这将宣布一个 target_frame
launch的论点,为第二只乌龟启动一个广播器,我们将产卵,听众将订阅这些转变。现在,您可以开始完整的turtle例程了: [待校准@8687]
ros2 launch learning_tf2_cpp turtle_tf2_demo.launch.py
你应该看看有两只海龟的海龟sim。在第二个终端窗口中,键入以下命令: [待校准@8688]
ros2 run turtlesim turtle_teleop_key
3检查结果 [待校准@8476]
要查看是否正常工作,只需使用箭头键绕开第一只乌龟 (确保终端窗口处于活动状态,而不是模拟器窗口),你会看到第二只乌龟跟着第一只! [待校准@8689]
总结
在本教程中,您学习了如何使用tf2访问帧转换。你也已经完成了你自己的turtlesim例程,这是你第一次在 Introduction to tf2 教程中尝试。 [待校准@8690]