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

Why is it necessary to declare ros transform broadcaster in main?

asked 2016-12-27 08:35:46 -0500

Manish Saroya gravatar image

Hi, I was trying to broadcast a tf in ros.

#include <ros/ros.h>
#include <tf/transform_broadcaster.h>
#include <tf/tf.h>
#include <geometry_msgs/TransformStamped.h> 

ros::Timer robot_pose_broadcaster;

void robotPoseCallBack(const ros::TimerEvent& eventalpha)
{
    tf::TransformBroadcaster robotPoseBroadcaster;
    geometry_msgs::TransformStamped robotPose;

    robotPose.header.stamp = ros::Time::now();
    robotPose.header.frame_id = "/map";
    robotPose.child_frame_id = "/base_link";

    robotPose.transform.translation.x = 0.0;
    robotPose.transform.translation.y = 0.0;
    robotPose.transform.translation.z = 0.0;
    robotPose.transform.rotation.x = 0.0;
    robotPose.transform.rotation.y = 0.0;
    robotPose.transform.rotation.z = 0.0;
    robotPose.transform.rotation.w = 0.9999;
    robotPoseBroadcaster.sendTransform(robotPose);
    ROS_INFO("DONE POSE BROADCASTING");
}

int main(int argc, char** argv)
{
        ros::init(argc, argv, "od_transform");
        ros::NodeHandle n;
        robot_pose_broadcaster = n.createTimer(ros::Duration(.1), robotPoseCallBack);

//      tf::TransformBroadcaster aphabetagamma;

        ros::spin();
        return 0;
}

This code broadcast nothing. But when I uncomment the below line.

tf::TransformBroadcaster aphabetagamma;

This code publishes transform between map and base_link even though I never use variable aphabetagamma. Can someone help me understand this.

Thanks.

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2016-12-27 09:32:04 -0500

NEngelhard gravatar image

You create the broadcaster in every call of the callback, use it immediately and destroys it immediately. Connecting to the listeners takes some time, so it's possible that you destroy the publisher before it could send something. So create a single publisher and use it in every callback. I'm not sure how the additional broadcaster changes something.

edit flag offensive delete link more

Comments

1

roscpp maintains publishers as singletons within the library, so creating a transform broadcaster in main has the side-effect of creating the publisher and allowing clients to connect before the second broadcaster is created in the callback.

ahendrix gravatar image ahendrix  ( 2016-12-27 12:33:01 -0500 )edit

The recommended practice is to keep the broadcaster as a global with the global callback, or as a class member, and have the callback as a member of that class.

ahendrix gravatar image ahendrix  ( 2016-12-27 12:34:15 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2016-12-27 08:35:46 -0500

Seen: 528 times

Last updated: Dec 27 '16