ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
The publishers for sensor_mshs, such as IMU, are created with reliability=best-effort and durability=volative 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)
import these types:
from rclpy.qos import QoSDurabilityPolicy
from rclpy.qos import QoSReliabilityPolicy
from rclpy.qos import QoSProfile
2 | No.2 Revision |
The publishers for sensor_mshs, sensor_msgs, such as IMU, are created with reliability=best-effort reliability=BEST_EFFORT and durability=volative 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)
import these types:
from rclpy.qos import QoSDurabilityPolicy
from rclpy.qos import QoSReliabilityPolicy
from rclpy.qos import QoSProfile
3 | No.3 Revision |
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