ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

tf broadcasting and listening in the same node

asked 2018-11-17 05:05:14 -0500

EunsanJo gravatar image

I am currently trying to make a perception part using tf.

My robot 's position is broadcasted to tf, and the robot tries to read obstacles using tf. I want to put this on the same node " " test1 "passed to lookupTransform argument target_frame does not exist. "Message is generated.

What happens when two nodes tf each succeed, and one node should not?

I think this problem is "time" and I have put in various times. ros :: Time (), ros :: Time (0). ros :: Time :: now (), ros :: Time :: now () - ros :: Duration (0.1) etc ..

But it was not all.

I tested with two threads on one node, which was a success. What is the problem?

#include "tf/transform_listener.h"
#include <ros/ros.h>
#include <tf/transform_broadcaster.h>

int main(int argc, char **argv) {
  ros::init(argc, argv, "tf_b");
  tf::TransformBroadcaster br;

  tf::Transform transform;
  tf::Quaternion q;
  ros::NodeHandle nh;

  transform.setOrigin(tf::Vector3(1.0, 1.0, 1.0));
  q.setRPY(0, 0, 0);

  ros::Rate loop_rate(10);
  while (ros::ok()) {

    ros::Time tGetTime = ros::Time::now();

    transform.setRotation(q);

    br.sendTransform(
        tf::StampedTransform(transform, tGetTime, "world", "test1"));

    tf::TransformListener listener;

    try {

      listener.waitForTransform("/test1", "/world", tGetTime,
                                ros::Duration(0.1));

      tf::StampedTransform transform;
      listener.lookupTransform("/test1", "/world", tGetTime, transform);

      ROS_INFO_STREAM(transform.getOrigin().getX());

    } catch (tf::TransformException &ex) {
      ROS_ERROR(ex.what());
    }

    ros::spinOnce();
    loop_rate.sleep();
  }
  return 0;
}

On top of that I've simplified the code to make it easier to understand.

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2018-11-17 05:25:32 -0500

gvdhoorn gravatar image

I think this problem is "time"

that might be, but perhaps not in the way you think.

You create your TransformListener inside your while loop. Don't do that. It needs time to fill its buffer, and you don't give it any.

Create it right after your NodeHandle, and use an AsyncSpinner.

edit flag offensive delete link more

Comments

1

Thank you. You are the best. I succeeded because I put 'listener creator' outside 'while loop'!

EunsanJo gravatar image EunsanJo  ( 2018-11-17 05:46:08 -0500 )edit
1

Using an AsyncSpinner might still be a good thing to do, just to avoid blocking updates to your TransformListener with long running operations.

gvdhoorn gravatar image gvdhoorn  ( 2018-11-17 06:01:49 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2018-11-17 05:05:14 -0500

Seen: 775 times

Last updated: Nov 17 '18