2 from __future__
import absolute_import
5 import paho.mqtt.client
as mqtt
8 from .bridge
import create_bridge
9 from .mqtt_client
import create_private_path_extractor
10 from .util
import lookup_object
13 def create_config(mqtt_client, serializer, deserializer, mqtt_private_path):
14 if isinstance(serializer, basestring):
16 if isinstance(deserializer, basestring):
20 binder.bind(
'serializer', serializer)
21 binder.bind(
'deserializer', deserializer)
22 binder.bind(mqtt.Client, mqtt_client)
23 binder.bind(
'mqtt_private_path_extractor', private_path_extractor)
29 rospy.init_node(
'mqtt_bridge_node')
32 params = rospy.get_param(
"~", {})
33 mqtt_params = params.pop(
"mqtt", {})
34 conn_params = mqtt_params.pop(
"connection")
35 mqtt_private_path = mqtt_params.pop(
"private_path",
"")
36 bridge_params = params.get(
"bridge", [])
39 mqtt_client_factory_name = rospy.get_param(
40 "~mqtt_client_factory",
".mqtt_client:default_mqtt_client_factory")
42 mqtt_client = mqtt_client_factory(mqtt_params)
45 serializer = params.get(
'serializer',
'json:dumps')
46 deserializer = params.get(
'deserializer',
'json:loads')
50 mqtt_client, serializer, deserializer, mqtt_private_path)
51 inject.configure(config)
54 mqtt_client.on_connect = _on_connect
55 mqtt_client.on_disconnect = _on_disconnect
56 mqtt_client.connect(**conn_params)
60 for bridge_args
in bridge_params:
64 mqtt_client.loop_start()
67 rospy.on_shutdown(mqtt_client.disconnect)
68 rospy.on_shutdown(mqtt_client.loop_stop)
73 rospy.loginfo(
'MQTT connected')
77 rospy.loginfo(
'MQTT disconnected')
80 __all__ = [
'mqtt_bridge_node']
def create_private_path_extractor(mqtt_private_path)
def lookup_object(object_path, package='mqtt_bridge')
def _on_disconnect(client, userdata, response_code)
def _on_connect(client, userdata, flags, response_code)
def create_config(mqtt_client, serializer, deserializer, mqtt_private_path)
def create_bridge(factory, msg_type, topic_from, topic_to, kwargs)