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

rostopic shows /imu message, but topic monitor shows "unknown"

asked 2020-09-03 06:00:55 -0500

rasga gravatar image

Hi everyone,

I have been looking for a solution since days now, going through every topics possible here I think.

TLDR: The terminal shows me the data coming from topic /imu but rqt doesn't, and it's impossible to create subscribers to this topic.

I am using ros2 foxy and Gazebo 11, and trying to set up a simulation environment using the turtlebot3.

I'll be using the example files to demonstrate my issue. I then start a gazebo simulation using:

ros2 launch turtlebot3_gazebo empty_world.launch.py

Then, I launch rqt in another terminal.

When I ask to show the data in the terminal, it works

ros2 topic echo /imu
header:
  stamp:
    sec: 11
    nanosec: 890000000
  frame_id: imu_link
orientation:
  x: 0.00029183817507114263
  y: 0.003497131776253974
  z: 0.0005251101507266362
  w: 0.9999937045597582
orientation_covariance:
- 0.0
- 0.0
- 0.0
- 0.0
- 0.0
- 0.0
- 0.0
- 0.0
- 0.0
angular_velocity:
  x: -0.00018927557211639842
  y: -0.00014382556517471507
  z: -5.107971493553278e-05
angular_velocity_covariance:
- 4.0e-08
- 0.0
- 0.0
- 0.0
- 4.0e-08
- 0.0
- 0.0
- 0.0
- 4.0e-08
linear_acceleration:
  x: -0.06601479616987073
  y: -0.006337202558406336
  z: 10.136475698659266
linear_acceleration_covariance:
- 0.00028900000000000003
- 0.0
- 0.0
- 0.0
- 0.00028900000000000003
- 0.0
- 0.0
- 0.0
- 0.00028900000000000003
---

But on rqt I can see this :

image description

The problem is not about the type sensor_msgs, since for joint_states it's showing data.

I also noticed that when I try to create a simple subscriber node to the topic /imu, the node wasn't receiving any message from the topic. It seems the callback function is never called. That is at least what I think is happening according to my investigations: I ask to print in the terminal when the callback function is called, and it never happens.

The code of the subscriber:

import rclpy
from rclpy.node import Node

from sensor_msgs.msg import Imu


class IMUSubscriber(Node):

    def __init__(self):
        super().__init__('imuSubscriber')
        self.subscription = self.create_subscription(
            Imu,
            'imu',
            self.listener_callback,
            10)
        self.subscription  # prevent unused variable warning

    def listener_callback(self, msg):
        self.get_logger().info('nanosec: %d' %(msg.header.stamp.nanosec))


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

    imuSubscriber = IMUSubscriber()

    rclpy.spin(imuSubscriber)

    # Destroy the node explicitly
    # (optional - otherwise it will be done automatically
    # when the garbage collector destroys the node object)
    imuSubscriber.destroy_node()
    rclpy.shutdown()


if __name__ == '__main__':
    main()

The debug messages from the terminal:

[DEBUG] [1599130457.222676544] [rcl]: Service initialized
[DEBUG] [1599130457.485559162] [rcl]: Initializing subscription for topic name 'imu'
[DEBUG] [1599130457.485710324] [rcl]: Expanded topic name '/imu'
[DEBUG] [1599130457.487330246] [rcl]: Subscription initialized
[DEBUG] [1599130457.488600191] [rcl]: Initializing wait set with '1' subscriptions, '2' guard conditions, '0' timers, '0' clients, '6' services
[DEBUG] [1599130457.488753062] [rcl]: Waiting without timeout
[DEBUG] [1599130457.488787299] [rcl]: Timeout calculated based on next scheduled timer: false
[DEBUG] [1599130457.488815255] [rcl]: Guard condition in wait set is ready
[DEBUG] [1599130457.489213867] [rcl]: Initializing wait set with '1' subscriptions, '2' guard conditions, '0' timers, '0' clients, '6' services
[DEBUG] [1599130457.489320660] [rcl]: Waiting without ...
(more)
edit retag flag offensive close merge delete

Comments

Same problem happens to me. Loading one of the gazebo demo worlds shows topics and messages containing data when using command line tools. However when subscribing to some of the topics with a custom script, only the subscriber count goes up, but no messages are received/callback is not triggered. For me also rqt_graph shows the connection, but rqt_topic shows 'unknown' in the hz column (although, again, I can view the rate by using ros2 topic hz).

I detailed my problem over at gazebo forum since I thought it might be caused by it, but I am not sure whether it is a ros or gazebo issue, so I am glad something similar is asked here already.

reza gravatar image reza  ( 2020-09-30 08:17:19 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
2

answered 2020-11-15 00:18:21 -0500

guru_florida gravatar image

updated 2020-11-15 00:43:42 -0500

The publishers for sensor_msgs, such as IMU, are created with reliability=BEST_EFFORT and durability=VOLATILE and are incompatible with the default QoS profile. You can inspect the QoS policy for the imu topic using:

ros2 topic info -v /imu

Node name: my_imu_plugin
Node namespace: /imu
Topic type: sensor_msgs/msg/Imu
Endpoint type: PUBLISHER
GID: 01.0f.7a.c1.3b.98.3e.00.01.00.00.00.00.00.39.03.00.00.00.00.00.00.00.00
QoS profile:
  Reliability: RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT
  Durability: RMW_QOS_POLICY_DURABILITY_VOLATILE
  Lifespan: 2147483651294967295 nanoseconds
  Deadline: 2147483651294967295 nanoseconds
  Liveliness: RMW_QOS_POLICY_LIVELINESS_AUTOMATIC
  Liveliness lease duration: 2147483651294967295 nanoseconds

Read about QoS compatibilities to see a table of what subscriber QoS settings are compatible with publishing QoS. Create your subscriber with the following QoS profile:

   imu_qos = QoSProfile(
        depth=1,
        reliability=QoSReliabilityPolicy.BEST_EFFORT,
        durability=QoSDurabilityPolicy.VOLATILE)

  self.imu_data = self.create_subscription(
        Imu,
        'imu',
        self.imu_callback,
        imu_qos)

or you can use the sensor-data preset profile instead:

imu_qos = rclpy.qos.QoSPresetProfiles.get_from_short_key('sensor_data')

import these types:

from rclpy.qos import QoSDurabilityPolicy
from rclpy.qos import QoSReliabilityPolicy
from rclpy.qos import QoSProfile
edit flag offensive delete link more

Comments

Not the OP, but this answer helped me with my similar problem and solved the issues, thank you! Problem for reference: gazebo forum

reza gravatar image reza  ( 2020-11-16 05:44:41 -0500 )edit

Question Tools

4 followers

Stats

Asked: 2020-09-03 05:59:33 -0500

Seen: 2,020 times

Last updated: Nov 15 '20