วันพฤหัสบดีที่ 29 มีนาคม พ.ศ. 2561

[Experimental] UDP Broadcast transport layer

referece: https://discourse.ros.org/t/experimental-udp-broadcast-transport-layer/2226 :


other link http://wiki.ros.org/ethzasl_message_transport#UDP_Multicasting

Hi all,
I made a proof of concept, meaning still experimental, of the UDP Broadcast transport layer and how it could work.
The final aim is to make a multimaster implementation with UDP Broadcast to avoid WiFi struggle.
I would like some advice of what is wrong and how to improve.
Architecture:
  1. Topic negotiation - Both the Subscriber/Publisher uses a TCP service to get the publishing port from the organizer.py
  2. Publisher serialize the packets into a Msg message then broadcast the packets to the port given by the organizer.
  3. The subscriber binds to the port, deserialize packets and either send it to the callback or publish it on the local master
Known limitations:
  • Not secure (publisher ip not checked, not crypted)
  • 64k maximum packet size (from IP protocol), tested only for non fragmented packets of less than 1k
  • ROS Indigo
  • Python 2.7
Usage:
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
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()
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()
  • created

    Jul '17
  • last reply

    Jul '17
  • 6

    replies

  • 410

    views

  • 5

    users

  • 3

    likes

  • 3

    links

  • 3
This is pretty cool stuff, and I like your goal of moving towards multi-master. How does it relate to UDPROS6?
It does not relate to UDPROS at all… :confused:
This is mainly a proof of concept to broadcast messages on IP layer instead of the Application layer. This avoid to struggle network on massive multi-robot environnement.
Then in what ways would you say they currently differ? Does UDPROS not yet support UDP broadcasting? For example, does the xmlrpc negotiation of transport layer for UDPROS not currently enable UDP broadcasting when more than one subscribers connect to the same port for the same topic for the same publisher?
9 DAYS LATER
Badly, UDPROS is unicast only. While it reduces the overhead over TCP, due to the unreliable connection, it can be improved to forward general information to a lot of robots. For 50 robots over the WiFi, while UDPROS will send 50 packets, it is possible to send only one broadcasted packet.
Again, this is only a proof of concept, to have a basic communication running. On this base, we can think about the problems encountered and how to tackle them and finally implement it inside ros_comm, for C++ and Python.

ไม่มีความคิดเห็น:

แสดงความคิดเห็น