Skip to content

Commit

Permalink
qos
Browse files Browse the repository at this point in the history
  • Loading branch information
InvincibleRMC committed Apr 30, 2024
1 parent 7983c3d commit 4c00c06
Show file tree
Hide file tree
Showing 2 changed files with 50 additions and 6 deletions.
2 changes: 2 additions & 0 deletions config/lampi.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -4,3 +4,5 @@ mqtt_ros_bridge:
topic: "devices/b827eb3d9134/lamp/set_config"
type: "lampi_msgs.msg:Lampi"
publish_on_ros: False
ros_qos: 1
mqtt_qos: 1
54 changes: 48 additions & 6 deletions mqtt_ros_bridge/bridge_node.py
Original file line number Diff line number Diff line change
@@ -1,12 +1,14 @@
import os
import sys
from typing import Any, Callable, Generic, cast
from enum import IntEnum
from typing import Any, Callable, Generic, cast, Literal

import paho.mqtt.client as MQTT
import rclpy
from rclpy._rclpy_pybind11 import RMWError
from rclpy.node import Node
# TODO this breaks humble
from rclpy.qos import QoSPresetProfiles
from rclpy.parameter import Parameter, parameter_dict_from_yaml_file
from rclpy.publisher import Publisher

Expand All @@ -15,16 +17,56 @@
from mqtt_ros_bridge.util import lookup_message


class QoSPresetProfilesInt(IntEnum):
UNKNOWN = 0
DEFAULT = 1
SYSTEM_DEFAULT = 2
SENSOR_DATA = 3
SERVICES_DEFAULT = 4
PARAMETERS = 5
PARAMETER_EVENTS = 6
ACTION_STATUS_DEFAULT = 7
BEST_AVAILABLE = 8

@staticmethod
def to_qos_profile(enum: int | 'QoSPresetProfilesInt') -> QoSPresetProfiles:
match enum:
case QoSPresetProfilesInt.UNKNOWN:
return QoSPresetProfiles.UNKNOWN
case QoSPresetProfilesInt.DEFAULT:
return QoSPresetProfiles.DEFAULT
case QoSPresetProfilesInt.SYSTEM_DEFAULT:
return QoSPresetProfiles.SYSTEM_DEFAULT
case QoSPresetProfilesInt.SENSOR_DATA:
return QoSPresetProfiles.SENSOR_DATA
case QoSPresetProfilesInt.SERVICES_DEFAULT:
return QoSPresetProfiles.SERVICES_DEFAULT
case QoSPresetProfilesInt.PARAMETERS:
return QoSPresetProfiles.PARAMETERS
case QoSPresetProfilesInt.PARAMETER_EVENTS:
return QoSPresetProfiles.PARAMETER_EVENTS
case QoSPresetProfilesInt.ACTION_STATUS_DEFAULT:
return QoSPresetProfiles.ACTION_STATUS_DEFAULT
case QoSPresetProfilesInt.BEST_AVAILABLE:
return QoSPresetProfiles.BEST_AVAILABLE
case _:
return QoSPresetProfiles.UNKNOWN


class TopicMsgInfo(Generic[MsgLikeT]):
"""Metadata about a single topic."""

def __init__(self, topic: str, msg_object_path: str,
publish_on_ros: bool, use_ros_serializer: bool = True) -> None:
publish_on_ros: bool, use_ros_serializer: bool = True,
ros_qos: int | QoSPresetProfilesInt = QoSPresetProfilesInt.DEFAULT,
mqtt_qos: Literal[0, 1, 2] = 0) -> None:

self.topic = topic
self.msg_type: MsgLikeT = cast(MsgLikeT, lookup_message(msg_object_path))
self.publish_on_ros = publish_on_ros
self.serializer = ROSDefaultSerializer if use_ros_serializer else JSONSerializer
self.ros_qos = QoSPresetProfilesInt.to_qos_profile(ros_qos)
self.mqtt_qos = mqtt_qos

def __str__(self) -> str:
return (f"Topic: {self.topic}, Message Type: {self.msg_type}, Publish on ROS:"
Expand Down Expand Up @@ -70,13 +112,13 @@ def __init__(self, args: list[str]) -> None:

for topic_info in self.topics.values():
if topic_info.publish_on_ros:
publisher = self.create_publisher(topic_info.msg_type, topic_info.topic, 10)
publisher = self.create_publisher(topic_info.msg_type, topic_info.topic, topic_info.ros_qos)
self.ros_publishers[topic_info.topic] = publisher
self.mqtt_client.subscribe(topic_info.topic)
self.mqtt_client.subscribe(topic_info.topic, qos=topic_info.mqtt_qos)
else:
callback = self.make_ros_callback(topic_info)
# TODO proper QOS?
self.create_subscription(topic_info.msg_type, topic_info.topic, callback, 10)
self.create_subscription(topic_info.msg_type, topic_info.topic, callback, topic_info.ros_qos)

self.mqtt_client.on_message = self.mqtt_callback

Expand Down Expand Up @@ -123,7 +165,7 @@ def make_ros_callback(self, topic_info: TopicMsgInfo[MsgLikeT]) -> Callable[[Msg
"""
def callback(msg: MsgLikeT) -> None:
self.get_logger().info(f'ROS RECEIVED: Topic: "{topic_info.topic}" Payload: "{msg}"')
self.mqtt_client.publish(topic_info.topic, topic_info.serializer.serialize(msg))
self.mqtt_client.publish(topic_info.topic, topic_info.serializer.serialize(msg), topic_info.mqtt_qos)

return callback

Expand Down

0 comments on commit 4c00c06

Please sign in to comment.