前往小程序,Get更优阅读体验!
立即前往
首页
学习
活动
专区
圈层
工具
发布
首页
学习
活动
专区
圈层
工具
MCP广场
社区首页 >专栏 >[ROS2基础] TF2使用细节

[ROS2基础] TF2使用细节

原创
作者头像
首飞
发布于 2022-06-05 13:01:16
发布于 2022-06-05 13:01:16
2.6K00
代码可运行
举报
文章被收录于专栏:ROS2ROS2
运行总次数:0
代码可运行

运行一个示例

安装依赖
代码语言:shell
AI代码解释
复制
sudo apt-get install ros-galactic-turtle-tf2-py ros-galactic-tf2-tools ros-galactic-tf-transformations
代码语言:shell
AI代码解释
复制
pip3 install transforms3d
运行示例

在不同的命令窗口中运行下面的命令

启动小乌龟窗口

代码语言:shell
AI代码解释
复制
ros2 launch turtle_tf2_py turtle_tf2_demo.launch.py

启动键盘控制节点

代码语言:shell
AI代码解释
复制
ros2 run turtlesim turtle_teleop_key

观察坐标转换的结果

代码语言:shell
AI代码解释
复制
ros2 run tf2_ros tf2_echo turtle2 turtle1
示例分析

本示例中启动了两只小乌龟Turtle1Turtle2TF发布器会将Turtle1相对于world坐标系的位置关系和Turtle2相对于world坐标系的位置关系发布出来。为了实现Turtle2跟随Turtle1的效果,程序中获取了Turtle1相对于Turtle2的位置关系并且将其折算成速度控制量。

代码语言:shell
AI代码解释
复制
        // 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);//这里得到的是from_frame_rel在to_frame_rel坐标系下的相对位置
        } 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;
        }

代码来自ros2_galactic_turorials/geometry_tutorials/turtle_tf2_cpp/src/turtle_tf2_listener.cpp

上面的示例代码可通过下面的方式获取:

代码语言:shell
AI代码解释
复制
git clone https://gitee.com/shoufei/ros2_galactic_turorials.git

或者

代码语言:shell
AI代码解释
复制
git clone git@github.com:shoufei403/ros2_galactic_tutorials.git

TF2树

tf2树表征了各个link的位置关系。一个link有且只有一个parent link。所以tf2树是不会形成闭环的。

代码语言:shell
AI代码解释
复制
ros2 run tf2_tools view_frames

用这个命令可以保存当前系统中tf2树的关系图(以pdf文件的形式保存在运行命令的目录下)。

静态TF发布器和动态TF发布器

静态TF发布器
编写代码发布TF(C++)

示例代码来自ros2_galactic_turorials/geometry_tutorials/turtle_tf2_cpp/src/static_turtle_tf2_broadcaster.cpp

代码语言:c++
AI代码解释
复制
#include <geometry_msgs/msg/transform_stamped.hpp>

#include <rclcpp/rclcpp.hpp>
#include <tf2/LinearMath/Quaternion.h>
#include <tf2_ros/static_transform_broadcaster.h>

#include <memory>

using std::placeholders::_1;

class StaticFramePublisher : public rclcpp::Node
{
public:
  explicit StaticFramePublisher(char * transformation[])
  : Node("static_turtle_tf2_broadcaster")
  {
    tf_publisher_ = std::make_shared<tf2_ros::StaticTransformBroadcaster>(this);

    // Publish static transforms once at startup
    this->make_transforms(transformation);
  }

private:
  void make_transforms(char * transformation[])
  {
    rclcpp::Time now = this->get_clock()->now();
    geometry_msgs::msg::TransformStamped t;

    t.header.stamp = now;
    t.header.frame_id = "world";
    t.child_frame_id = transformation[1];

    t.transform.translation.x = atof(transformation[2]);
    t.transform.translation.y = atof(transformation[3]);
    t.transform.translation.z = atof(transformation[4]);
    tf2::Quaternion q;
    q.setRPY(
      atof(transformation[5]),
      atof(transformation[6]),
      atof(transformation[7]));
    t.transform.rotation.x = q.x();
    t.transform.rotation.y = q.y();
    t.transform.rotation.z = q.z();
    t.transform.rotation.w = q.w();

    tf_publisher_->sendTransform(t);
  }
  std::shared_ptr<tf2_ros::StaticTransformBroadcaster> tf_publisher_;
};

int main(int argc, char * argv[])
{
  auto logger = rclcpp::get_logger("logger");

  // Obtain parameters from command line arguments
  if (argc != 8) {
    RCLCPP_INFO(
      logger, "Invalid number of parameters\nusage: "
      "ros2 run learning_tf2_cpp static_turtle_tf2_broadcaster "
      "child_frame_name x y z roll pitch yaw");
    return 1;
  }

  // As the parent frame of the transform is `world`, it is
  // necessary to check that the frame name passed is different
  if (strcmp(argv[1], "world") == 0) {
    RCLCPP_INFO(logger, "Your static turtle name cannot be 'world'");
    return 1;
  }

  // Pass parameters and initialize node
  rclcpp::init(argc, argv);
  rclcpp::spin(std::make_shared<StaticFramePublisher>(argv));
  rclcpp::shutdown();
  return 0;
}
编写代码代码发布TF(Python)

示例代码来自ros2_galactic_turorials/geometry_tutorials/turtle_tf2_py/turtle_tf2_py/turtle_tf2_broadcaster.py

代码语言:python
代码运行次数:0
运行
AI代码解释
复制
from geometry_msgs.msg import TransformStamped

import rclpy
from rclpy.node import Node

from tf2_ros import TransformBroadcaster

import tf_transformations

from turtlesim.msg import Pose


class FramePublisher(Node):

    def __init__(self):
        super().__init__('turtle_tf2_frame_publisher')

        # Declare and acquire `turtlename` parameter
        self.declare_parameter('turtlename', 'turtle')
        self.turtlename = self.get_parameter(
            'turtlename').get_parameter_value().string_value

        # Initialize the transform broadcaster
        self.br = TransformBroadcaster(self)

        # Subscribe to a turtle{1}{2}/pose topic and call handle_turtle_pose
        # callback function on each message
        self.subscription = self.create_subscription(
            Pose,
            f'/{self.turtlename}/pose',
            self.handle_turtle_pose,
            1)


    def handle_turtle_pose(self, msg):
        t = TransformStamped()

        # Read message content and assign it to
        # corresponding tf variables
        t.header.stamp = self.get_clock().now().to_msg()
        t.header.frame_id = 'world'
        t.child_frame_id = self.turtlename

        # Turtle only exists in 2D, thus we get x and y translation
        # coordinates from the message and set the z coordinate to 0
        t.transform.translation.x = msg.x
        t.transform.translation.y = msg.y
        t.transform.translation.z = 0.0

        # For the same reason, turtle can only rotate around one axis
        # and this why we set rotation in x and y to 0 and obtain
        # rotation in z axis from the message
        q = tf_transformations.quaternion_from_euler(0, 0, msg.theta)
        t.transform.rotation.x = q[0]
        t.transform.rotation.y = q[1]
        t.transform.rotation.z = q[2]
        t.transform.rotation.w = q[3]

        # Send the transformation
        self.br.sendTransform(t)


def main():
    rclpy.init()
    node = FramePublisher()
    try:
        rclpy.spin(node)
    except KeyboardInterrupt:
        pass

    rclpy.shutdown()
手动以命令行形式发布TF

角度用欧拉角表示

x/y/z偏移的单位是米,roll/pitch/yaw偏移的单位是rad

Publish a static coordinate transform to tf2 using an x/y/z offset in meters and roll/pitch/yaw in radians. In our case, roll/pitch/yaw refers to rotation about the x/y/z-axis, respectively.

代码语言:shell
AI代码解释
复制
ros2 run tf2_ros static_transform_publisher x y z yaw pitch roll frame_id child_frame_id

角度用四元数表示

Publish a static coordinate transform to tf2 using an x/y/z offset in meters and quaternion.

代码语言:shell
AI代码解释
复制
ros2 run tf2_ros static_transform_publisher x y z qx qy qz qw frame_id child_frame_id
在launch文件中发布TF
代码语言:python
代码运行次数:0
运行
AI代码解释
复制
from launch import LaunchDescription
from launch_ros.actions import Node

def generate_launch_description():
   return LaunchDescription([
      Node(
            package='tf2_ros',
            executable='static_transform_publisher',
            arguments = ['0', '0', '1', '0', '0', '0', 'world', 'mystaticturtle']
      ),
   ])
动态TF发布器

动态的tf发布一般是编写代码来实现的。

C++实现动态TF发布

示例代码来自ros2_galactic_turorials/geometry_tutorials/turtle_tf2_cpp/src/turtle_tf2_broadcaster.cpp

代码语言:C++
AI代码解释
复制
#include <geometry_msgs/msg/transform_stamped.hpp>

#include <rclcpp/rclcpp.hpp>
#include <tf2/LinearMath/Quaternion.h>
#include <tf2_ros/transform_broadcaster.h>
#include <turtlesim/msg/pose.hpp>

#include <memory>
#include <string>

using std::placeholders::_1;

class FramePublisher : public rclcpp::Node
{
public:
  FramePublisher()
  : Node("turtle_tf2_frame_publisher")
  {
    // Declare and acquire `turtlename` parameter
    this->declare_parameter<std::string>("turtlename", "turtle");
    this->get_parameter("turtlename", turtlename_);

    // Initialize the transform broadcaster
    tf_broadcaster_ =
      std::make_unique<tf2_ros::TransformBroadcaster>(*this);

    // Subscribe to a turtle{1}{2}/pose topic and call handle_turtle_pose
    // callback function on each message
    std::ostringstream stream;
    stream << "/" << turtlename_.c_str() << "/pose";
    std::string topic_name = stream.str();

    subscription_ = this->create_subscription<turtlesim::msg::Pose>(
      topic_name, 10,
      std::bind(&FramePublisher::handle_turtle_pose, this, _1));
  }

private:
  void handle_turtle_pose(const std::shared_ptr<turtlesim::msg::Pose> msg)
  {
    rclcpp::Time now = this->get_clock()->now();
    geometry_msgs::msg::TransformStamped t;

    // Read message content and assign it to
    // corresponding tf variables
    t.header.stamp = now;
    t.header.frame_id = "world";
    t.child_frame_id = turtlename_.c_str();

    // Turtle only exists in 2D, thus we get x and y translation
    // coordinates from the message and set the z coordinate to 0
    t.transform.translation.x = msg->x;
    t.transform.translation.y = msg->y;
    t.transform.translation.z = 0.0;

    // For the same reason, turtle can only rotate around one axis
    // and this why we set rotation in x and y to 0 and obtain
    // rotation in z axis from the message
    tf2::Quaternion q;
    q.setRPY(0, 0, msg->theta);
    t.transform.rotation.x = q.x();
    t.transform.rotation.y = q.y();
    t.transform.rotation.z = q.z();
    t.transform.rotation.w = q.w();

    // Send the transformation
    tf_broadcaster_->sendTransform(t);
  }
  rclcpp::Subscription<turtlesim::msg::Pose>::SharedPtr subscription_;
  std::unique_ptr<tf2_ros::TransformBroadcaster> tf_broadcaster_;
  std::string turtlename_;
};

int main(int argc, char * argv[])
{
  rclcpp::init(argc, argv);
  rclcpp::spin(std::make_shared<FramePublisher>());
  rclcpp::shutdown();
  return 0;
}
Python实现动态TF发布

示例代码来自ros2_galactic_turorials/geometry_tutorials/turtle_tf2_py/turtle_tf2_py/turtle_tf2_broadcaster.py

代码语言:python
代码运行次数:0
运行
AI代码解释
复制
from geometry_msgs.msg import TransformStamped

import rclpy
from rclpy.node import Node

from tf2_ros import TransformBroadcaster

import tf_transformations

from turtlesim.msg import Pose


class FramePublisher(Node):

    def __init__(self):
        super().__init__('turtle_tf2_frame_publisher')

        # Declare and acquire `turtlename` parameter
        self.declare_parameter('turtlename', 'turtle')
        self.turtlename = self.get_parameter(
            'turtlename').get_parameter_value().string_value

        # Initialize the transform broadcaster
        self.br = TransformBroadcaster(self)

        # Subscribe to a turtle{1}{2}/pose topic and call handle_turtle_pose
        # callback function on each message
        self.subscription = self.create_subscription(
            Pose,
            f'/{self.turtlename}/pose',
            self.handle_turtle_pose,
            1)


    def handle_turtle_pose(self, msg):
        t = TransformStamped()

        # Read message content and assign it to
        # corresponding tf variables
        t.header.stamp = self.get_clock().now().to_msg()
        t.header.frame_id = 'world'
        t.child_frame_id = self.turtlename

        # Turtle only exists in 2D, thus we get x and y translation
        # coordinates from the message and set the z coordinate to 0
        t.transform.translation.x = msg.x
        t.transform.translation.y = msg.y
        t.transform.translation.z = 0.0

        # For the same reason, turtle can only rotate around one axis
        # and this why we set rotation in x and y to 0 and obtain
        # rotation in z axis from the message
        q = tf_transformations.quaternion_from_euler(0, 0, msg.theta)
        t.transform.rotation.x = q[0]
        t.transform.rotation.y = q[1]
        t.transform.rotation.z = q[2]
        t.transform.rotation.w = q[3]

        # Send the transformation
        self.br.sendTransform(t)


def main():
    rclpy.init()
    node = FramePublisher()
    try:
        rclpy.spin(node)
    except KeyboardInterrupt:
        pass

    rclpy.shutdown()

监听TF数据

实际上,就是是获取两个坐标系之间的相对位置。

C++版本

示例代码来自ros2_galactic_turorials/geometry_tutorials/turtle_tf2_cpp/src/turtle_tf2_listener.cpp

代码语言:C++
AI代码解释
复制
#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);//这里得到的是from_frame_rel在to_frame_rel坐标系下的位置
        } 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;
}

增加超时时间的写法

代码语言:c++
AI代码解释
复制
        try {
          rclcpp::Time now = this->get_clock()->now();
          transformStamped = tf_buffer_->lookupTransform(
            toFrameRel,
            fromFrameRel,
            now,
            50ms);//获取当前时间的tf关系并且允许50ms的超时时间
        } 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;
        }

示例代码来自ros2_galactic_turorials/geometry_tutorials/turtle_tf2_cpp/src/turtle_tf2_listener_timeout.cpp

可运行下面的命令查看效果

代码语言:shell
AI代码解释
复制
ros2 launch turtle_tf2_cpp turtle_tf2_demo_timeout.launch.py
代码语言:shell
AI代码解释
复制
ros2 run turtlesim turtle_teleop_key

获取历史时间点的tf关系

代码语言:c++
AI代码解释
复制
        try {
          rclcpp::Time now = this->get_clock()->now();
          rclcpp::Time when = now - rclcpp::Duration(5, 0);
          transformStamped = tf_buffer_->lookupTransform(
              toFrameRel,
              now,
              fromFrameRel,
              when,
              "world",
              50ms);
        } 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;
        }

示例代码来自ros2_galactic_turorials/geometry_tutorials/turtle_tf2_cpp/src/turtle_tf2_listener_time_travel.cpp

运行命令

代码语言:shell
AI代码解释
复制
ros2 launch turtle_tf2_cpp turtle_tf2_demo_time_travel.launch.py
代码语言:shell
AI代码解释
复制
ros2 run turtlesim turtle_teleop_key

python版本

示例代码来自ros2_galactic_turorials/geometry_tutorials/turtle_tf2_py/turtle_tf2_py/turtle_tf2_listener.py

代码语言:python
代码运行次数:0
运行
AI代码解释
复制
import math

from geometry_msgs.msg import Twist

import rclpy
from rclpy.node import Node

from tf2_ros import TransformException
from tf2_ros.buffer import Buffer
from tf2_ros.transform_listener import TransformListener

from turtlesim.srv import Spawn


class FrameListener(Node):

    def __init__(self):
        super().__init__('turtle_tf2_frame_listener')

        # Declare and acquire `target_frame` parameter
        self.declare_parameter('target_frame', 'turtle1')
        self.target_frame = self.get_parameter(
            'target_frame').get_parameter_value().string_value

        self.tf_buffer = Buffer()
        self.tf_listener = TransformListener(self.tf_buffer, self)

        # Create a client to spawn a turtle
        self.spawner = self.create_client(Spawn, 'spawn')
        # Boolean values to store the information
        # if the service for spawning turtle is available
        self.turtle_spawning_service_ready = False
        # if the turtle was successfully spawned
        self.turtle_spawned = False

        # Create turtle2 velocity publisher
        self.publisher = self.create_publisher(Twist, 'turtle2/cmd_vel', 1)

        # Call on_timer function every second
        self.timer = self.create_timer(1.0, self.on_timer)

    def on_timer(self):
        # Store frame names in variables that will be used to
        # compute transformations
        from_frame_rel = self.target_frame
        to_frame_rel = 'turtle2'

        if self.turtle_spawning_service_ready:
            if self.turtle_spawned:
                # Look up for the transformation between target_frame and turtle2 frames
                # and send velocity commands for turtle2 to reach target_frame
                try:
                    now = rclpy.time.Time()
                    trans = self.tf_buffer.lookup_transform(
                        to_frame_rel,
                        from_frame_rel,
                        now)  #这里得到的是from_frame_rel在to_frame_rel坐标系下的位置
                except TransformException as ex:
                    self.get_logger().info(
                        f'Could not transform {to_frame_rel} to {from_frame_rel}: {ex}')
                    return

                msg = Twist()
                scale_rotation_rate = 1.0
                msg.angular.z = scale_rotation_rate * math.atan2(
                    trans.transform.translation.y,
                    trans.transform.translation.x)

                scale_forward_speed = 0.5
                msg.linear.x = scale_forward_speed * math.sqrt(
                    trans.transform.translation.x ** 2 +
                    trans.transform.translation.y ** 2)

                self.publisher.publish(msg)
            else:
                if self.result.done():
                    self.get_logger().info(
                        f'Successfully spawned {self.result.result().name}')
                    self.turtle_spawned = True
                else:
                    self.get_logger().info('Spawn is not finished')
        else:
            if self.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
                request = Spawn.Request()
                request.name = 'turtle2'
                request.x = float(4)
                request.y = float(2)
                request.theta = float(0)
                # Call request
                self.result = self.spawner.call_async(request)
                self.turtle_spawning_service_ready = True
            else:
                # Check if the service is ready
                self.get_logger().info('Service is not ready')


def main():
    rclpy.init()
    node = FrameListener()
    try:
        rclpy.spin(node)
    except KeyboardInterrupt:
        pass

    rclpy.shutdown()

增加超时时间的写法

代码语言:python
代码运行次数:0
运行
AI代码解释
复制
trans = self._tf_buffer.lookup_transform(
   to_frame_rel,
   from_frame_rel,
   now,
   timeout=rclpy.time.Duration(seconds=1.0))

示例代码来自ros2_galactic_turorials/geometry_tutorials/turtle_tf2_py/turtle_tf2_py/turtle_tf2_listener_timeout.py

运行命令

代码语言:shell
AI代码解释
复制
ros2 launch turtle_tf2_py turtle_tf2_demo_timeout.launch.py
代码语言:shell
AI代码解释
复制
ros2 run turtlesim turtle_teleop_key

获取历史时间点的tf关系

代码语言:python
代码运行次数:0
运行
AI代码解释
复制
                try:
                    when = self.get_clock().now() - rclpy.time.Duration(seconds=5.0)
                    trans = self.tf_buffer.lookup_transform_full(
                            target_frame=to_frame_rel,
                            target_time=rclpy.time.Time(),
                            source_frame=from_frame_rel,
                            source_time=when,
                            fixed_frame='world',
                            timeout=rclpy.time.Duration(seconds=0.05))
                except (LookupException, ConnectivityException, ExtrapolationException):
                    self.get_logger().info('transform not ready')
                    return

示例代码来自ros2_galactic_turorials/geometry_tutorials/turtle_tf2_py/turtle_tf2_py/turtle_tf2_listener_time_travel.py

运行命令

代码语言:shell
AI代码解释
复制
ros2 launch turtle_tf2_py turtle_tf2_demo_time_travel.launch.py
代码语言:shell
AI代码解释
复制
ros2 run turtlesim turtle_teleop_key

TF 调试工具

打印两个link的相对位置关系

代码语言:shell
AI代码解释
复制
ros2 run tf2_ros tf2_echo turtle2 turtle1

保存tf关系框图

代码语言:shell
AI代码解释
复制
ros2 run tf2_tools view_frames

监控两个link的转换延时

代码语言:shell
AI代码解释
复制
ros2 run tf2_ros tf2_monitor turtle2 turtle1

四元数与欧拉角转换

因为使用TF的过程中常常涉及到坐标转换。这会涉及到角度的表示方法。

通常我们会有两种表示角度的方法,一种是欧拉角,一种是四元数。欧拉角是更为直观的表示方法,但因为死锁的问题,在进行坐标变换计算时常常是使用四元数的。

ROS2中,有两个数据类型表示四元数。它们是来自tf2功能包的tf2::Quaternion类型和来自geometry_msgs功能包的geometry_msgs::msg::Quaternion类型。我们可以通过tf2_geometry_msgs包来进行两个类型的互相转换。

C++的写法

代码语言:c++
AI代码解释
复制
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
...

tf2::Quaternion tf2_quat, tf2_quat_from_msg;
tf2_quat.setRPY(roll, pitch, yaw);
// Convert tf2::Quaternion to geometry_msgs::msg::Quaternion
geometry_msgs::msg::Quaternion msg_quat = tf2::toMsg(tf2_quat);

// Convert geometry_msgs::msg::Quaternion to tf2::Quaternion
tf2::convert(msg_quat, tf2_quat_from_msg);
// or
tf2::fromMsg(msg_quat, tf2_quat_from_msg);

Python的写法

代码语言:python
代码运行次数:0
运行
AI代码解释
复制
from geometry_msgs.msg import Quaternion
...

# Create a list of floats, which is compatible with tf2
# Quaternion methods
quat_tf = [0.0, 1.0, 0.0, 0.0]

# Convert a list to geometry_msgs.msg.Quaternion
msg_quat = Quaternion(x=quat_tf[0], y=quat_tf[1], z=quat_tf[2], w=quat_tf[3])

欧拉角和四元数之间的转换可以用下面的方式

欧拉角转四元数

C++版本

代码语言:c++
AI代码解释
复制
#include <tf2/LinearMath/Quaternion.h>

tf2::Quaternion myQuaternion;
myQuaternion.setRPY(1.5707, 0, -1.5707);  // Create this quaternion from roll/pitch/yaw (in radians)
ROS_INFO("%f  %f  %f  %f" ,myQuaternion.x(),myQuaternion.y(),myQuaternion.z(),myQuaternion.w());  // Print the quaternion components (0,0,0,1)

Python版本

代码语言:python
代码运行次数:0
运行
AI代码解释
复制
import tf_transformations
...

q = tf_transformations.quaternion_from_euler(1.5707, 0, -1.5707)
print(f'The quaternion representation is x: {q[0]} y: {q[1]} z: {q[2]} w: {q[3]}.')

四元数转欧拉角

C++版本

tf2/utils.h中定义了如下方法。

代码语言:c++
AI代码解释
复制
/** Return the yaw, pitch, roll of anything that can be converted to a tf2::Quaternion
 * The conventions are the usual ROS ones defined in tf2/LineMath/Matrix3x3.h
 * \param a the object to get data from (it represents a rotation/quaternion)
 * \param yaw yaw
 * \param pitch pitch
 * \param roll roll
 */
template<class A>
void getEulerYPR(const A & a, double & yaw, double & pitch, double & roll)
{
  tf2::Quaternion q = impl::toQuaternion(a);
  impl::getEulerYPR(q, yaw, pitch, roll);
}

/** Return the yaw of anything that can be converted to a tf2::Quaternion
 * The conventions are the usual ROS ones defined in tf2/LineMath/Matrix3x3.h
 * This function is a specialization of getEulerYPR and is useful for its
 * wide-spread use in navigation
 * \param a the object to get data from (it represents a rotation/quaternion)
 * \param yaw yaw
 */
template<class A>
double getYaw(const A & a)
{
  tf2::Quaternion q = impl::toQuaternion(a);
  return impl::getYaw(q);
}

Python版本

代码语言:python
代码运行次数:0
运行
AI代码解释
复制
import tf_transformations

rpy = tf_transformations.euler_from_quaternion([0.06146124, 0, 0, 0.99810947])

更多细节请查看下面的文章:

https://docs.ros.org/en/galactic/Tutorials/Tf2/Quaternion-Fundamentals.html

tf2_ros::MessageFilter

https://docs.ros.org/en/galactic/Tutorials/Tf2/Using-Stamped-Datatypes-With-Tf2-Ros-MessageFilter.html

To do this turtle1 must listen to the topic where turtle3’s pose is being published, wait until transforms into the desired frame are ready, and then do its operations. To make this easier the tf2_ros::MessageFilter is very useful. The tf2_ros::MessageFilter will take a subscription to any ROS 2 message with a header and cache it until it is possible to transform it into the target frame.

tf2_ros::MessageFilter 的主要作用是,等待目标frame已经缓冲在tf树中。这样的话转换到该frame将是可行的。AMCL模块中处理激光数据就是一个好的例子。

代码语言:c++
AI代码解释
复制
void
AmclNode::initMessageFilters()
{
  laser_scan_sub_ = std::make_unique<message_filters::Subscriber<sensor_msgs::msg::LaserScan>>(
    rclcpp_node_.get(), scan_topic_, rmw_qos_profile_sensor_data);

  laser_scan_filter_ = std::make_unique<tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan>>(
    *laser_scan_sub_, *tf_buffer_, odom_frame_id_, 10, rclcpp_node_, transform_tolerance_);

  laser_scan_connection_ = laser_scan_filter_->registerCallback(
    std::bind(
      &AmclNode::laserReceived,
      this, std::placeholders::_1));
}

odom_frame_id_tf树中可转换时,接受到激光数据后开始执行回调函数laserReceived 。在laserReceived 中通过odom_frame_id_ 获取到当前的odom 数据。也就是说,使用tf2_ros::MessageFilter 达到了,等能获取odom 数据时再处理激光数据的效果。

下面是官方的一个示例。可以参考其写法。

代码语言:c++
AI代码解释
复制
#include <geometry_msgs/msg/point_stamped.hpp>
#include <message_filters/subscriber.h>

#include <rclcpp/rclcpp.hpp>
#include <tf2_ros/buffer.h>
#include <tf2_ros/create_timer_ros.h>
#include <tf2_ros/message_filter.h>
#include <tf2_ros/transform_listener.h>
#ifdef TF2_CPP_HEADERS
  #include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
#else
  #include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#endif

#include <chrono>
#include <memory>
#include <string>

using namespace std::chrono_literals;

class PoseDrawer : public rclcpp::Node
{
public:
  PoseDrawer()
  : Node("turtle_tf2_pose_drawer")
  {
    // Declare and acquire `target_frame` parameter
    this->declare_parameter<std::string>("target_frame", "turtle1");
    this->get_parameter("target_frame", target_frame_);

    typedef std::chrono::duration<int> seconds_type;
    seconds_type buffer_timeout(1);

    tf2_buffer_ = std::make_shared<tf2_ros::Buffer>(this->get_clock());
    // Create the timer interface before call to waitForTransform,
    // to avoid a tf2_ros::CreateTimerInterfaceException exception
    auto timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(
      this->get_node_base_interface(),
      this->get_node_timers_interface());
    tf2_buffer_->setCreateTimerInterface(timer_interface);
    tf2_listener_ =
      std::make_shared<tf2_ros::TransformListener>(*tf2_buffer_);

    point_sub_.subscribe(this, "/turtle3/turtle_point_stamped");
    tf2_filter_ = std::make_shared<tf2_ros::MessageFilter<geometry_msgs::msg::PointStamped>>(
      point_sub_, *tf2_buffer_, target_frame_, 100, this->get_node_logging_interface(),
      this->get_node_clock_interface(), buffer_timeout);
    // Register a callback with tf2_ros::MessageFilter to be called when transforms are available
    tf2_filter_->registerCallback(&PoseDrawer::msgCallback, this);//等待需要的tf关系就绪,一就绪有数据就进入到回调函数中。
  }

private:
  void msgCallback(const geometry_msgs::msg::PointStamped::SharedPtr point_ptr)
  {
    geometry_msgs::msg::PointStamped point_out;
    try {
      tf2_buffer_->transform(*point_ptr, point_out, target_frame_);//point_out的值是turtle3想对于target_frame_的坐标
      RCLCPP_INFO(
        this->get_logger(), "Point of turtle3 in frame of turtle1: x:%f y:%f z:%f\n",
        point_out.point.x,
        point_out.point.y,
        point_out.point.z);
    } catch (tf2::TransformException & ex) {
      RCLCPP_WARN(
        // Print exception which was caught
        this->get_logger(), "Failure %s\n", ex.what());
    }
  }
  std::string target_frame_;
  std::shared_ptr<tf2_ros::Buffer> tf2_buffer_;
  std::shared_ptr<tf2_ros::TransformListener> tf2_listener_;
  message_filters::Subscriber<geometry_msgs::msg::PointStamped> point_sub_;
  std::shared_ptr<tf2_ros::MessageFilter<geometry_msgs::msg::PointStamped>> tf2_filter_;
};

int main(int argc, char * argv[])
{
  rclcpp::init(argc, argv);
  rclcpp::spin(std::make_shared<PoseDrawer>());
  rclcpp::shutdown();
  return 0;
}

参考:

https://docs.ros.org/en/galactic/Tutorials/Tf2/Tf2-Main.html

原创声明:本文系作者授权腾讯云开发者社区发表,未经许可,不得转载。

如有侵权,请联系 cloudcommunity@tencent.com 删除。

原创声明:本文系作者授权腾讯云开发者社区发表,未经许可,不得转载。

如有侵权,请联系 cloudcommunity@tencent.com 删除。

评论
登录后参与评论
暂无评论
推荐阅读
如何维护爬虫代理
为了保证网络爬虫再爬虫业务中能更高效稳定运行,在使用代理时需要维护一个好的爬虫代理IP池。那如何维护爬虫代理IP呢?
用户6172015
2020/10/13
7330
隧道IP的原理与使用
随着大数据时代的发展,网络爬虫的用户也越来越多,随之HTTP代理成了网络爬虫的不可缺少的一部分。使用过http代理的都清楚,,使用代理ip的基础流程是这样的:爬虫用户使用程序发送请求到代理服务器,代理服务器将请求转发到目标网站,目标网站处理完后返回结果,代理服务器收到反馈到结果后将信息转发到客户端,这样就完成了一次代理请求。整个过程中,代理服务器就充当了一个转发请求和结果的作用。HTTP代理分为隧道代理和外网代理IP。有通过API提取的也有动态转发的爬虫代理。那什么是隧道IP呢?
用户6172015
2020/12/10
1.8K0
使用python制作属于自己的地铁图
在日常出行中有时候会需要用到地毯地铁,网上找的地铁线路图大多数都不太清晰,而且有水印,对本人这种视力不好的人来说看起来是真的不方便。我想可以通过站点数据制作属于自己的线路图。主要还是缺乏站点数据,有数据了图自然就有了。经过网上查询,发现高德地图上有专门的地铁线路图,但是不能导出数据或图片,只好自己想办法抓取了,下面我们就通过使用python获取自己所在城市的地铁站点数据。抓取思路是这样,首先,用浏览器高德地图官网 ,搜索地铁, 进入地铁线路网站如下,网址:http://map.amap.com/subway/index.html,然后我们通过python爬虫爬取各线路各站点的 名称、经纬度 信息,以供后续使用。在获取数据的时候我们可能会遇到反爬机制,像封IP的等行为。在访问的过程中我们可以加上代理以防万一,简单的爬虫过程如下:// 要访问的目标页面
小白学大数据
2024/06/08
1940
python如何抓取微博定时热搜
不知道大家在工作无聊时,是不是总想掏出手机,刷刷微博看下热搜在讨论什么有趣的话题,但又不方便直接打开微博浏览,今天就和大家分享一个有趣的小爬虫,那就是如何定时采集微博热搜榜&热评,下具体的实现方法我们接下来慢慢讲。首先我们需要找到微博排行、热度、标题,以及详情页的链接。热搜首页链接https://weibo.com/hot/search我们通过这个链接获取500条数据,热搜榜采集代码, 然后发起请求,简单的代码如下<?php // 要访问的目标页面
小白学大数据
2024/06/08
2180
更换HTTP代理的方式
爬虫代理IP被应用到了很多的场景中,无论是对于家庭网络还是工作中的网络来说,为我们平时的工作提供了很多服务,有其是网络爬虫,爬虫代理IP更是不可缺少的一部分。面对网络上许多IP代理商,选择代理可以根据不同的使用方向进行选择。
用户6172015
2020/12/21
4950
HTTP代理的应用场景
很多爬虫工作者都知道,爬虫工作的进行离不开HTTP代理IP的支持。除了网络爬虫,那么HTTP代理IP适合于那些应用环境呢?
用户6172015
2020/11/18
6450
判断代理IP是否是高匿
普通匿名代理能隐藏客户机的真实IP,但会改变我们的请求信息,服务器端有可能会认为我们使用了代理。不过使用此种代理时,虽然被访问的网站不能知道你的ip地址,但仍然可以知道你在使用代理,当然某些能够侦测ip的网页仍然可以查到你的ip。 高匿名代理不改变客户机的请求,这样在服务器看来就像有个真正的客户浏览器在访问它,这时客户的真实IP是隐藏的,服务器端不会认为我们使用了代理。
用户6172015
2021/02/01
3K0
python帮你更快选择国考职位
2022年国考明天开始报名,11月28日举行公共科目笔试,本次招考共有75个部门、23个直属机构参加,计划招录3.12万人。很多小伙伴都在考虑是否要报公务员,但是却不知道适合自己的岗位有什么,那么今天我们就来利用Python找出适合你的岗位吧!我们可以根据以往的报考职位表,找到以下的报考限制因素:专业、学历、政治面貌、基层工作年限等。 以我们计算机本科专业为例,没有任何的基层工作经验,以这样的条件筛选,那么我们可以报考的岗位有多少呢?我们可以利用python获取数据,但是因为暂时还看不到具体的岗位数据,我们就以去年的岗位为例。数据获取代码如下:
小白学大数据
2024/06/08
1040
正确的使用HTTP代理
HTTP代理对于网络爬虫是一种很常见的协议,HTTP代理协议也是大数据时代不可缺少的一部分。HTTP代理在网络爬虫中发挥出了他大量用途。HTTP代理其实有许多用途,例如:刷票,爬虫,抢单,刷单,等等一系列业务 都适合HTTP代理。其实对于网络爬虫工作来着说,许多网络工作者都不知道如何使用HTTP代理。那么如何才能正确使用HTTP代理呢?
用户6172015
2020/11/16
1.4K0
python3和scrapy使用隧道代理问题以及代码
近期,我参与了一个需要爬取国家食品药品监督局数据的项目,但该网站存在IP屏蔽机制。因此,我需要在Scrapy框架中实现自动IP切换,才能完成任务。然而,尽管我使用了第三方库scrapy-proxys和代理API接口,但测试并不成功。
小白学大数据
2023/03/02
9130
优化爬虫程序使用代理IP时出现的TIME_WAIT和CLOSE_WAIT状态
为了提高爬虫程序的效率,我们通常使用代理IP来同时访问多个网站,避免被封禁。但是,使用代理IP也会带来一些问题。在Linux系统下,我们经常会遇到TIME_WAIT和CLOSE_WAIT状态的问题。
jackcode
2023/05/05
4270
优化爬虫程序使用代理IP时出现的TIME_WAIT和CLOSE_WAIT状态
如何在 Docker 容器内部使用外部代理服务器访问HTTP网络资源
在某些情况下,我们可能需要在 Docker 容器内部向外部代理服务器发送请求。例如,当我们需要访问外部网络资源时,我们可能需要通过代理服务器来访问它们。另一个例子是在企业网络中,可能需要使用代理服务器来访问互联网资源。然而,由于 Docker 容器的网络隔离性质,使得容器默认情况下无法直接连接到外部代理服务器。因此,为了让 Docker 容器内部能够通过代理服务器访问外部网络资源,我们需要进行相应的网络配置,包括在容器启动时传递--network host选项来允许容器使用主机网络接口,以及在容器内部设置http_proxy和https_proxy环境变量来配置代理服务器。通过这些配置,Docker 容器就能够顺利地连接到外部代理服务器并访问所需的网络资源。
jackcode
2023/03/22
4.2K0
如何在 Docker 容器内部使用外部代理服务器访问HTTP网络资源
python3和scrapy使用隧道代理问题以及代码
最近有个项目需要爬取药监局数据,对方有ip屏蔽机制。所以我需要在scrapy中实现ip自动切换,才能够完成爬取任务。在此之前,我先使用过第三方库scrapy-proxys加上代理api接口,可能是代码没有完善好,导致测试没有成功。 所以这次选择使用隧道的方式来测试看下,使用的是python3和scrapy库一起测试看下效果。
小白学大数据
2024/06/08
1820
自动化数据处理:使用Selenium与Excel打造的数据爬取管道
随着互联网信息爆炸式增长,获取有效数据成为决策者的重要任务。人工爬取数据不仅耗时且效率低下,因此自动化数据处理成为一种高效解决方案。本文将介绍如何使用Selenium与Excel实现数据爬取与处理,结合代理IP技术构建一个可稳定运行的数据爬取管道,专门用于从WIPO(世界知识产权组织)的Brand Database网站(branddb.wipo.int)中获取专利和技术信息。
jackcode
2024/10/15
2310
自动化数据处理:使用Selenium与Excel打造的数据爬取管道
PHP爬虫性能优化:从多线程到连接池的实现
随着网络数据的爆炸式增长,爬虫技术成为数据获取的重要工具。从市场调研到用户行为分析,爬虫的应用无处不在。然而,在实际应用中,我们常常遇到爬虫性能不足的问题:单线程处理效率低下、请求超时、数据采集量庞大却无法及时处理等,这些问题严重限制了爬虫技术的潜能。
jackcode
2024/12/02
1750
PHP爬虫性能优化:从多线程到连接池的实现
Selenium+代理爬取需要模拟用户交互的网站
在日常爬虫采集网站的过程中,部分数据价值较高的网站,会限制访客的访问行为。这种时候建议通过登录的方式,获取目标网站的cookie,然后再使用cookie配合代理IP进行数据采集分析。今天我们就介绍下如何使用Selenium库来爬取网页数据,特别是那些需要模拟用户交互的动态网页。
小白学大数据
2023/05/18
3930
如何伪装本地IP
我们通过互联网上网的的时候,浏览各大网站时,个人信息随时都有可能被泄露,信息泄露都是悄无声息的发生,不会被用户发现。一旦发现我们自己的的信息被泄露的时候,说明肯定给自己造成了一定的损失。
用户6172015
2020/10/26
2.5K0
付费代理的使用
相对免费代理来说,付费代理的稳定性更高。本节将介绍爬虫付费代理的相关使用过程。 一、付费代理分类 付费代理分为两类: 一类提供接口获取海量代理,按天或者按量收费,如讯代理; 一类搭建了代理隧道,直
崔庆才
2018/06/25
4.2K0
影响HTTP代理速度的几个因素
随着大数据时代的发展,代理IP慢慢成为了中很多人经常使用的上网采集的一种工具。特别是对于一些专业的爬网络爬虫用户来说,这种代理是他们生活工作必不可少的工具。就如同我们平时上网一样。当然使用代理IP,肯定会考虑到速度问题。就像我们的本地IP一样访问一个网站一样也有延迟。当我们验证代理IP地址时,会间隔几秒。这间隔的几秒就是服务器的响应时间,时间越快,说明速度快,使用起来也快,好用许多。
用户6172015
2020/12/31
8820
解决网络爬虫使用代理IP效果变差的原因
现在的互联网大数据时代中,代理IP是网络爬虫不可缺少的一部分。大数据采集最简单直接有效的方法就是使用网络爬虫,不仅速度快,提高了业务率,而且还能更加有效率的采集到数据。网络爬虫都很清楚,如果使用本IP去采集大数据,是不可能完全任务的,所以就需要使用代理IP。
用户6172015
2020/11/26
4990
相关推荐
如何维护爬虫代理
更多 >
领券
问题归档专栏文章快讯文章归档关键词归档开发者手册归档开发者手册 Section 归档