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

Can't receive data in python node

asked 2019-09-03 02:31:06 -0500

madmax gravatar image

updated 2019-09-03 10:10:14 -0500

Hi,

I don't know how to debug this:
I took the python demo listener and changed it to subscribe to odometry.
But when I subscribe to my running cpp node which publishes odom, I don't receive any data ...
If I use a cmd publisher like ros2 topic pub /odom nav_msgs/msg/Odometry, listener receives data..
Also if I use my own cpp odom publisher and the cmd line publisher at the same time, I only receive data from cmd publisher...

But echo gives me data from both publishers...

Namespace is correct, topic is correct.

I am running on empty now ...

from std_msgs.msg import String
from nav_msgs.msg import Odometry

class Listener(Node):

    def __init__(self):
        super().__init__('odom_listener')
        self.sub = self.create_subscription(Odometry, 'odom', self.chatter_callback, 10)

    def chatter_callback(self, msg):
        self.get_logger().info('I heard odom')


def main(args=None):
    rclpy.init(args=args)

    node = Listener()
    rclpy.spin(node)

    node.destroy_node()
    rclpy.shutdown()


if __name__ == '__main__':
    main()

As requested cpp publisher:

   odomPub = this->create_publisher<Odom>( "odom", rclcpp::SensorDataQoS() );
edit retag flag offensive close merge delete

Comments

My guess would be this has something to do with the namespace of the topic you're using. Have you tried using /odom in your code instead of odom?

PeteBlackerThe3rd gravatar image PeteBlackerThe3rd  ( 2019-09-03 05:52:36 -0500 )edit

@madmax What is the output of your CPP node? Add a code snippet of the CPP node publisher, it would be helpful.

SamsAutonomy gravatar image SamsAutonomy  ( 2019-09-03 09:36:31 -0500 )edit

@madmax More questions :) What does ros2 topic list return? With both publishers running.

Also, how do you know which publisher is reaching your callback when you: Also if I use my own cpp odom publisher and the cmd line publisher at the same time, I only receive data from cmd publisher...

SamsAutonomy gravatar image SamsAutonomy  ( 2019-09-03 11:16:55 -0500 )edit

2 Answers

Sort by ยป oldest newest most voted
2

answered 2019-09-03 12:24:39 -0500

sloretz gravatar image

It looks like the QoS settings on the publisher and subscriber are incompatible. Change the QoS settings on either the publisher or the listener to match. See the page About Quality of Service Settings for more info.

The C++ publisher is using rclcpp::SensorDataQoS(), which uses the sensor data QoS profile. The Python subscriber is just specifying the queue size, which means it uses the default profile with the given queue size of 10. The incompatibility comes from the reliability setting. The sensor data profile specifies best effort while the default profile uses reliable. According to the QoS compatibilities table, a subscriber requiring reliable will not connect to a publisher providing only best effort reliability.

edit flag offensive delete link more

Comments

Good hint! Coming from ros 1 where its not that strict...

madmax gravatar image madmax  ( 2019-09-03 15:13:42 -0500 )edit

This hint helped me find the answer with (somewhat) code that solved this for me: https://index.ros.org//doc/ros2/Conce...

deb0ch gravatar image deb0ch  ( 2020-03-09 09:20:42 -0500 )edit
0

answered 2020-11-18 23:02:03 -0500

@sloretz is right, just here to add some code for better understanding, future viewers.

So if your publisher is using

rclcpp::SensorDataQoS()

Then in your python subscriber subscribe with same QOS setting, for example I subscribe to NavsatFix message with following;

import rclpy
from rclpy.node import Node
from rclpy.qos import qos_profile_sensor_data

from sensor_msgs.msg import NavSatFix

def __init__(self):
    super().__init__('gps_waypoint_collector')

    self.subscription = self.create_subscription(
        NavSatFix,
        '/gps/fix',
        self.listener_callback, qos_profile_sensor_data
    )
    self.subscription  # prevent unused variable warning


def listener_callback(self, msg):
    print(msg.latitude, msg.longitude, msg.altitude)
edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2019-09-03 02:31:06 -0500

Seen: 2,066 times

Last updated: Nov 18 '20