/multimaster_udp

UDP broadcast transport layer, with view of reimplementing the multimaster with UDP to run over WiFi

Primary LanguagePythonMIT LicenseMIT

multimaster_udp

Multimaster is a originally fork of the original repo on bitbucket (multimaster) from daenny. Now it focuses on getting UDP broadcast then UDP multicast message passing.

UDP broadcast

Architecture

  • One port for each topic/data_type
  • Ports chosen are the default port (11411) +1 for each pair (topic/data_type)
  • Robots (Subscribers/Publishers) calls the service organizer/topic with a multimaster_udp/AdvertiseUDP message to get the port number
  • The multimaster_udp/AdvertiseUDP message consist of a multimaster_udp/TopicInfo message you have to fill in, omitting the port, the answer from the organizer.py will be the multimaster_udp/TopicInfo message with the port filled in.

USAGE

Smallest UDP subscriber

#!/usr/bin/env python
import rospy

from multimaster_udp.transport import UDPSubscriber
from std_msgs.msg import String

def callback(data, topic):
    global counter
    counter += 1
    print data, "\n received",counter, "UDP messages from \n", topic

def main():
    global counter
    counter = 0
    rospy.init_node("smallest_subscriber_udp")
    # if the callback is not defined (None), it will publish locally 
    # to the equivalent topic.
    sub = UDPSubscriber("hello", String, callback=None)
    rospy.spin()

if __name__ == '__main__':
    main()

Smallest UDP broadcast publisher

#!/usr/bin/env python
import rospy

from multimaster_udp.transport import UDPPublisher
from std_msgs.msg import String

def main():
    rospy.init_node("smallest_broadcast_publisher_udp")

    msg = String("World")
    pub = UDPPublisher("hello", String)

    rate = rospy.Rate(100)
    while not rospy.is_shutdown():
        pub.publish(msg)
        rate.sleep()

if __name__ == '__main__':
    main()

Test the current status

Build the repo, then execute:

roscore &
rosrun multimaster_udp organizer.py

# in another terminal
rosrun multimaster_udp smallest_subscriber_udp.py
# in another terminal
rosrun multimaster_udp smallest_publisher_udp.py

master_sync

Original library

Usage

Yaml configuration file

local_pubs: [local_topics_to_register_at_foreign_master]
foreign_pubs: [foreign_topics_to_register_at_local_master]
local_services: [local_services_to_register_at_foreigner]
foreign_services: [foreign_services_to_register_at_local]

Example

The local master is running a turtle which publish its position and state while using a service to set the destination to travel to.

  • topics :
    • /turtle0/position
    • /turtle0/state
  • services:
    • /turtle0/setGoal

The foreign master is managing the turtle(s), publishing the map. It wants to call the turtle0 service.

  • /master/map

The master_sync.py node will be ran onto the turtle computer and the configuration for this example is:

local_pubs: ["/turtle0/position", "/turtle0/state"]
foreign_pubs: ["/master/map"]
local_services: ["/turtle0/setGoal"]
foreign_services: []

Credits