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

Empty ConnectionHeader in MessageEvent (C++)

asked 2019-10-23 06:33:21 -0500

RainerK gravatar image

Hi all,

I am trying to get the publisher of a topic message in a C++ subscriber.

However, when I subscribe to the topic via a MessageEvent<> callback and try to get the connection header via event.getConnectionHeaderPtr(), I only get a nullptr. This happens when publishing from a C++ node and via rostopic pub ....

It works when the subscriber is a python node (I am able to get the publisher name via data._connection_header["callerid"]). I am not able to find further resources online to solve the issue. Does anyone have an idea on what could be the cause?

This question seems to be related, but was fixed (the fix should be included in my system).

System information:

  • Platform: Ubuntu 18, kernel 4.15.0-65-generic
  • ROS Melodic (from official packages)

Code excerpts:

// in namespace basic_topic
template <class Msg>
struct SubscriberCallback
{
    SubscriberCallback();
    void operator()(const ros::MessageEvent<Msg>& event);
};

template <class Msg>
void SubscriberCallback<Msg>::operator()(const ros::MessageEvent<Msg>& event)
{
    ROS_INFO_STREAM("Publisher: " << event.getPublisherName() 
                    << " header: " << event.getConnectionHeaderPtr());
    typename Msg::ConstPtr msg = event.getConstMessage();
    // ...
}

class Subscriber
{
public:
    // ...
    void subscribe(ros::NodeHandle& node, uint32_t bufferSize = 10);

private:
    // ...
    ros::Subscriber subInt32;
};

void Subscriber::subscribe(ros::NodeHandle& node, uint32_t queueSize)
{    
    // ...
    subInt32 = node.subscribe<std_msgs::Int32>("Int32", queueSize, SubscriberCallback<std_msgs::Int32>());
}

In main:

int main(int argc, char** argv)
{
    static const std::string nodeName = "test_basic_subscriber";
    static const uint32_t queueSize = 100;

    ros::init(argc, argv, nodeName);
    ros::NodeHandle node;

    basic_topic::Subscriber subscriber;
    subscriber.subscribe(node, queueSize);

    ros::Time last = ros::Time::now();
    const ros::Duration duration(0.5);

    while (ros::ok())
    {
        ros::spinOnce();
        // ...
    }
}

Result when running:

[ INFO] [1571830014.487512531]: Publisher: unknown_publisher header: 0

Example publish via rostopic pub: (Result is the same as when publishing from C++ node)

rostopic pub /Int32 std_msgs/Int32 "data: 42"

Example subscriber node in python:

#! /usr/bin/env python2

import rospy
from std_msgs.msg import Int32

def callback(data):
    # type: (Int32) -> None
    print("Received {} from node {}.".format(
        data.data,
        data._connection_header["callerid"]))

def run_subscriber():
    rospy.init_node("basic_test_subscriber")
    sub = rospy.Subscriber("Int32", Int32, callback)
    # pub = rospy.Publisher("BasicTopic/reportInt", Int32, queue_size=10)
    rospy.spin()


if __name__ == "__main__":
    run_subscriber()

Result when publishing from rostopic pub:

Received 42 from node /rostopic_11868_1571830133181.

Result when publishing from C++ node:

Received 42 from node /test_basic_publisher.
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
3

answered 2019-11-15 09:27:03 -0500

RainerK gravatar image

updated 2019-11-15 09:27:25 -0500

I could solve the problem. The callback function had to be casted explicitly to the correct boost::function type:

void Subscriber::subscribe(ros::NodeHandle& node, uint32_t queueSize)
{    
    // ...
    using BoostCallback = boost::function<void(const ros::MessageEvent<std_msgs::Int32>&>;
    subInt32 = node.subscribe<std_msgs::Int32>("Int32", queueSize, BoostCallback(SubscriberCallback<std_msgs::Int32>()));
}

I guess the internal overloading of NodeHande::subscribe() did not work properly for my case, causing invalid/uninitialized MessageEvents to my callback.

edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2019-10-23 06:32:23 -0500

Seen: 617 times

Last updated: Nov 15 '19