ROS运行乌龟demo,出现[ERROR] [1595917385.143325803]: "turtle2" passed to lookupTransform argument target_frame does not exist.

请问,我依照书上的代码运行start_demo_with_listener.launch,结果第二个小海龟只出现在左下角不向第一个海龟运动,而且命令行提示错误,错误如下

[ERROR] [1595917385.143325803]: "turtle2" passed to lookupTransform argument target_frame does not exist.

我记得以前按视频单独运行tf的广播器和监听器时,小海龟是可以动的,现在单独运行也不成了

运行demo之后,发现没有生成tf树,PDF显示no tf data recieved,单独运行tf的广播器和监听器也是同样的情况

广播器代码如下

#include <ros/ros.h>
#include <tf/transform_broadcaster.h>
#include <turtlesim/Pose.h>

std::string turtle_name;

void poseCallback(const turtlesim::PoseConstPtr& msg)
{
    // 广播TF消息之前需要定义TF广播器
    static tf::TransformBroadcaster br;

    // 根据当前乌龟位姿,设置相对于世界坐标系world的tf::transform类型的坐标变换
    tf::Transform transform;
    transform.setOrigin(tf::Vector3(msg->x, msg->y, 0.0)); // 平移
    tf::Quaternion q; // 四元数
    q.setRPY(0, 0, msg->theta); // 旋转
    transform.setRotation(q);

    // 发布坐标变换
    br.sendTransform(tf::StampedTransform(transform, ros::Time::now(), "world", turtle_name)); // 发布的消息类型是tf::StampedTransform
}

int main(int argc, char** argv)
{
    // argc 是 argument count 的缩写,表示传入main函数的参数个数
    // argv 是 argument vector 的缩写,表示传入main函数的参数序列或指针,第一个参数argv[0]是程序的名称,并且包含了程序所在的完整路径,所以确切的说需要我们输入的main函数的参数个数应该是argc-1个

    // 初始化节点
    ros::init(argc, argv, "my_tf_broadcaster");

    if (argc != 2)
    {
        ROS_ERROR("need turtle name as argument!");
        return -1;
    }
    turtle_name = argv[1];

    // 订阅乌龟的pose信息
    ros::NodeHandle node;
    ros::Subscriber sub = node.subscribe(turtle_name + "pose", 10, &poseCallback); // 注册回调函数poseCallback

    // 循环等待回调函数
    ros::spin();

    return 0;
}


监听器代码

#include <ros/ros.h>
#include <tf/transform_listener.h>
#include <geometry_msgs/Twist.h>
#include <turtlesim/Spawn.h>

int main(int argc, char** argv)
{
    ros::init(argc, argv, "my_tf_listener");

    ros::NodeHandle node;

    // 通过服务调用,产生第二只小海龟
    ros::service::waitForService("spawn");
    ros::ServiceClient add_turtle = node.serviceClient<turtlesim::Spawn>("spawn");
    turtlesim::Spawn srv;
    add_turtle.call(srv);

    // 定义turtle2的速度控制发布器
    ros::Publisher turtle_vel = node.advertise<geometry_msgs::Twist>("turtle2/cmd_vel", 10);

    // TF监听器
    tf::TransformListener listener; // 缓存十秒

    ros::Rate rate(10.0);
    while (node.ok())
    {
        tf::StampedTransform transform;

        rate.sleep();
        try
        {
            // 查找turtle2和turtle1的坐标变换
            listener.waitForTransform("/turtle2", "/turtle1", ros::Time(0), ros::Duration(3.0)); //target_frame, source_frame
            listener.lookupTransform("/turtle2", "/turtle1", ros::Time(0), transform);
        }
        catch (tf::TransformException &ex)
        {
            ROS_ERROR("%s", ex.what());
            ros::Duration(1.0).sleep();
            continue;
        }

        // 根据tuetle1和turtle2之间的坐标变换,计算turtle2运动需要的线速度和角速度
        // 并发布速度控制指令,使turtle2向turtle1移动
        geometry_msgs::Twist vel_msg;
        vel_msg.angular.z = 4.0 * atan2(transform.getOrigin().y(), transform.getOrigin().x());
        vel_msg.linear.x = 0.5 * sqrt(pow(transform.getOrigin().x(), 2) + pow(transform.getOrigin().y(), 2));
        turtle_vel.publish(vel_msg);        
    }
    return 0;
}

launch文件

<launch>
    <!-- 海龟仿真器 -->
    <node pkg="turtlesim" type="turtlesim_node" name="sim"/>

    <!-- 键盘控制器 -->
    <node pkg="turtlesim" type="turtle_teleop_key" name="teleop" output="screen"/>

    <!-- 两只海龟的TF广播 -->
    <node pkg="learning_tf" type="turtle_tf_broadcaster" args="/turtle1" name="turtle1_tf_broadcaster"/>
    <node pkg="learning_tf" type="turtle_tf_broadcaster" args="/turtle2" name="turtle2_tf_broadcaster"/>

    <!-- 监听TF广播,并控制turtle2移动 -->
    <node pkg="learning_tf" type="turtle_tf_listener" name="listener"/>
    <!-- <node pkg="learning_tf" type="turtle_tf_listener" name="listener"/> --> 

</launch>

请问怎么解决

解决方法参考
https://blog.csdn.net/start_from_scratch/article/details/50762293