ROS 中 transform 变化关于 ros::Time::now() 和 ros::Time(0)的区别测试

328 阅读2分钟

本文已参与「新人创作礼」活动,一起开启掘金创作之路。


首先贴上简单的验证代码,方便大家验证,欢迎提出问题一起交流讨论~

@TOC


一丶代码

1. 工程一:transform 发布节点

/***************** tf发布文件 **********/
#include "ros/ros.h"
#include <tf/transform_listener.h>
#include <tf/transform_broadcaster.h>
#include <tf/tf.h>


int main(int argc, char *argv[])
{
    setlocale(LC_ALL,"");
    ros::init(argc,argv,"tf_pub");
    ros::NodeHandle nh;
    tf::TransformBroadcaster odom2BaseBroadcaster_;

    ros::Rate rate(1);
    double x = 0;
    double y = 0;
    while(ros::ok())
    {
        tf::Transform odom2Base;
        tf::Quaternion quaternion;

        ros::Time currentTime = ros::Time::now();
        odom2Base.setOrigin(tf::Vector3(x, y, 0));
        quaternion.setRPY(0, 0, 0);

        odom2Base.setRotation(quaternion);
        ROS_INFO("sendTransformodom2base robotpose : %f %f %f", x,y,0.0);
        odom2BaseBroadcaster_.sendTransform(tf::StampedTransform(odom2Base, currentTime, "odom", "base_link"));
        
        x += 1.0;       
        rate.sleep();
        ros::spinOnce();
    }
    
    return 0;
}
cmake_minimum_required(VERSION 3.0.2)
project(tftestpub)

find_package(catkin REQUIRED COMPONENTS
  rospy 
  std_msgs
  roscpp
  tf
  tf2
)

add_executable(${PROJECT_NAME}_node src/main.cpp)
target_link_libraries(${PROJECT_NAME}_node
  ${catkin_LIBRARIES}
)

catkin_package(
)

include_directories(
# include
  ${catkin_INCLUDE_DIRS}
)

2. 工程二:transform 接收节点

/***********  tf发布函数订阅文件 **********/
//1.包含头文件
#include "ros/ros.h"
#include <tf/transform_listener.h>
#include <tf/transform_broadcaster.h>
#include <tf/tf.h>

int main(int argc, char *argv[])
{
    setlocale(LC_ALL,"");
    // 2.初始化 ROS 节点
    ros::init(argc,argv,"dynamic_tf_sub");
    ros::NodeHandle nh;
    // 3.创建 TF 订阅节点
    tf2_ros::Buffer buffer;
    tf2_ros::TransformListener listener(buffer);

    ros::Rate r(3);

    while (ros::ok())
    {
        tf::TransformListener transform_listener;
        tf::StampedTransform base2odom;
        ROS_INFO("getTransformMap2Odom, robotPose");
        try{
            transform_listener.waitForTransform("odom", "base_link",ros::Time(0), ros::Duration(1));
            transform_listener.lookupTransform("odom", "base_link", ros::Time(0), base2odom);
            ROS_INFO("getTransformMap2Odom, robotPose %f %f %f",base2odom.getOrigin().x(), base2odom.getOrigin().y(),base2odom.getOrigin().z());
        }
            catch(tf::TransformException &ex){
            ROS_ERROR("%s", ex.what());
        }


        r.sleep();  
        ros::spinOnce();
    }


    return 0;
}
cmake_minimum_required(VERSION 3.0.2)
project(tftestsub)

find_package(catkin REQUIRED COMPONENTS
  rospy 
  std_msgs
  roscpp
  tf
  tf2
)

add_executable(${PROJECT_NAME}_node src/main.cpp)
target_link_libraries(${PROJECT_NAME}_node
  ${catkin_LIBRARIES}
)

catkin_package(
)

include_directories(
# include
  ${catkin_INCLUDE_DIRS}
)

二丶测试结果分析

1. ros::Time::now() 获取当前的时间

            transform_listener.waitForTransform("odom", "base_link",ros::Time::now(), ros::Duration(0.1));
            transform_listener.lookupTransform("odom", "base_link", ros::Time::now(), base2odom);

在这里插入图片描述

2. ros::Time(0) 使用缓冲中最新的tf数据

在这里插入图片描述

3. ros::Time::now() + ros::Time(0) 等待到最新时间,再取缓存数据

            transform_listener.waitForTransform("odom", "base_link",ros::Time::now(), ros::Duration(0.1));
            transform_listener.lookupTransform("odom", "base_link", ros::Time(0), base2odom);

在这里插入图片描述 但是并没有达到我想要得效果,因为在博客ROS学习之TF变换的时间戳中,证明 tf 会进行类似插值的计算,找到一个近似请求的时间戳的坐标变换,不过例子中是ROS中的tf2,或者是我验证的方法存在问题,后面有需要准备再复现一下该博客的现象。


同时在本篇下记录一个遇到的tf问题: 修复前:

    //current pose is from map to base_link
    tf::Transform map2base = tf::Transform(tf::createQuaternionFromRPY(0, 0,pose.sensor_pose.phi),
        tf::Point(pose.sensor_pose.x, pose.sensor_pose.y, 0.0));

    tf::StampedTransform base2odom;
    tf::TransformBroadcaster map2OdomBroadcaster; 
    tf::TransformListener transformListener_;

    try {
        transformListener_.lookupTransform(baseFrame_, odomFrame_, ros::Time(0), base2odom);
    }
    catch(tf::TransformException &ex){
        ROS_ERROR("%s", ex.what());
        return;
    }

    tf::Transform map2odom = map2base * base2odom;
    tf::StampedTransform map2odomTf = tf::StampedTransform(map2odom, ros::Time::now(), mapFrame_, odomFrame_);
    map2OdomBroadcaster.sendTransform(map2odomTf);
	LocationFusionRos fusionRos;
	fusionRos.sendTransformMap2Odom(robotPose);

修复后:

    //current pose is from map to base_link
    tf::Transform map2base = tf::Transform(tf::createQuaternionFromRPY(0, 0,pose.sensor_pose.phi),
        tf::Point(pose.sensor_pose.x, pose.sensor_pose.y, 0.0));

    tf::StampedTransform base2odom;
    static tf::TransformBroadcaster map2OdomBroadcaster; 
    static tf::TransformListener transformListener_;

    try {
        transformListener_.lookupTransform(baseFrame_, odomFrame_, ros::Time(0), base2odom);
    }
    catch(tf::TransformException &ex){
        ROS_ERROR("%s", ex.what());
        return;
    }

    tf::Transform map2odom = map2base * base2odom;
    tf::StampedTransform map2odomTf = tf::StampedTransform(map2odom, ros::Time::now(), mapFrame_, odomFrame_);
    map2OdomBroadcaster.sendTransform(map2odomTf);

LocationFusionRos fusionRos; 放入文件中去定义

问题原因分析:怀疑是因为 tf 对象每次重新发布 都是重新 new 的,所以 tf 的缓存里可能没有数据,修复后就没出现找不到 taget frame 的问题,欢迎讨论~