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

ROS message sent but not received

asked 2015-08-04 09:44:51 -0500

jdorfsman gravatar image

I'm using ROS in my project and I need to send one message from time to time. I have this function:

void RosNetwork::sendMessage(string msg, string channel) {
    _mtx.lock();
    ros::Publisher chatter_pub = _n.advertise<std_msgs::String>(channel.c_str(),10);
    ros::Rate loop_rate(10);
    std_msgs::String msgToSend;
    msgToSend.data = msg.c_str();
    chatter_pub.publish(msgToSend);
    loop_rate.sleep();
    cout << "Message Sent" << endl;
    _mtx.unlock();
}

And I have this in python:

def callbackFirst(data):
    #rospy.loginfo(rospy.get_caller_id() + "I heard %s", data.data)
    print("Received message from first filter")

def callbackSecond(data):
    #rospy.loginfo(rospy.get_caller_id() + "I heard %s", data.data)
    print("Received message from second filter")

def listener():
    rospy.Subscriber("FirstTaskFilter", String, callbackFirst)
    print("subscribed to FirstTaskFilter")
    rospy.Subscriber("SecondTaskFilter", String, callbackSecond)
    print("subscribed to SecondTaskFilter")
    rospy.spin()

The listener is a thread in python. I get to the function sendMessage (I see in the terminal "Message Sent" a lot of times) but I don't see that the python script receives the message.

Update: I tested the python callback with rostopic pub /FirstTaskFilter std_msgs/String "test" and this works perfectly.

Any thought?

edit retag flag offensive close merge delete

Comments

Well, what is the topic of the Publisher? Check with rosnode info <YOUR_PUBLISHER_NODE> which topics it sends. I guess this is a simple remapping issue...

You can also visualize this with rosrun rqt_graph rqt_graph.

mgruhler gravatar image mgruhler  ( 2015-08-04 10:24:40 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
1

answered 2015-08-04 10:23:57 -0500

Sebastian Kasperski gravatar image

You should use advertise() only once at startup, not every time you want to send a message.

edit flag offensive delete link more

Comments

Thanks, I did that and that solved it.

jdorfsman gravatar image jdorfsman  ( 2015-08-04 10:36:32 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2015-08-04 09:44:51 -0500

Seen: 1,148 times

Last updated: Aug 04 '15