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

Revision history [back]

click to hide/show revision 1
initial version

@Mac is exactly right. I'm adding another answer only to suggest another common design pattern: use a C++ class to defer variable initialization. The example below includes a TransformBroadcaster private variable, which will create a NodeHandle. It gets initialized when Publisher publisher is created.

#include <ros/ros.h>
#include <tf2_ros/transform_broadcaster.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#include <sensor_msgs/Imu.h>

class Publisher
{
private:

  tf2_ros::TransformBroadcaster tf_broadcaster_;
  ros::Subscriber imu_sub_;

  void imuCallback(const sensor_msgs::ImuConstPtr &msg)
  {
    geometry_msgs::TransformStamped imu_tf;
    imu_tf.header.stamp = ros::Time::now();
    imu_tf.header.frame_id = "base_link";
    imu_tf.child_frame_id = "imu_link";
    imu_tf.transform.rotation = msg->orientation;
    tf_broadcaster_.sendTransform(imu_tf);
  }

public:

  Publisher(ros::NodeHandle& nh_priv)
  {
    imu_sub_ = nh_priv.subscribe<sensor_msgs::Imu>("/imu/data", 10, &Publisher::imuCallback, this);
  }
};

int main(int argc, char **argv)
{
  ros::init(argc, argv, "tf_publish");
  ros::NodeHandle nh{""};
  ros::NodeHandle nh_priv{"~"};
  Publisher publisher{nh_priv};
  ros::spin();
  return 0;
}

@Mac is exactly right. I'm adding another answer only to suggest another common design pattern: use a C++ class to defer variable initialization. The example below includes a TransformBroadcaster private variable, which will create a NodeHandle. It gets initialized when Publisher publisher is created.

#include <ros/ros.h>
#include <tf2_ros/transform_broadcaster.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#include <sensor_msgs/Imu.h>

class Publisher
{
private:

  tf2_ros::TransformBroadcaster tf_broadcaster_;
  ros::Subscriber imu_sub_;

  void imuCallback(const sensor_msgs::ImuConstPtr &msg)
  {
    geometry_msgs::TransformStamped imu_tf;
    imu_tf.header.stamp = ros::Time::now();
    imu_tf.header.frame_id = "base_link";
    imu_tf.child_frame_id = "imu_link";
    imu_tf.transform.rotation = msg->orientation;
    tf_broadcaster_.sendTransform(imu_tf);
  }

public:

  Publisher(ros::NodeHandle& nh_priv)
  {
    imu_sub_ = nh_priv.subscribe<sensor_msgs::Imu>("/imu/data", 10, &Publisher::imuCallback, this);
  }
};

int main(int argc, char **argv)
{
  ros::init(argc, argv, "tf_publish");
  ros::NodeHandle nh{""};
nh("");
  ros::NodeHandle nh_priv{"~"};
nh_priv("~");
  Publisher publisher{nh_priv};
publisher(nh_priv);
  ros::spin();
  return 0;
}