<> <> == Overview == The node '''adhoc_communication''' allows you to exchange data over an ad-hoc network protocol via dynamic source routing. The package allows you to exchange data over serveral roscores. The node will send the data to the destination robot and publish the message on the destination on a given topic. The routing is done with the hostname of the robots. The node implements three types of routing: === Unicast === One-to-One communication - the data will be transmitted to one destination robot. === Multicast === One-to-Many communication. Every robot has its own multicast group, which will be created when the '''adhoc_communication''' node is starting. The name of the group will be "'''mc_'''" plus the hostname. If a robots hostname is "'''bob'''", its multicast group is called "'''mc_bob'''". All other robots can join a group with the service '''[[#join_mc_group|join_mc_group]]'''. All members of a group can send data within this group. === Broadcast === Broadcasts will be received and published from all robots. == Related Documentation == Please refer to the following paper to retrieve more information on the node: {{{ @InProceedings{Andre2014, Title = {Coordinated Multi-Robot Exploration: Out of the Box Packages for {ROS}}, Author = {Andre, T. and Neuhold, D. and Bettstetter, C.}, Booktitle = {Proc. of IEEE GLOBECOM WiUAV Workshop}, Year = {2014}, Month = dec, } }}} You may obtain the paper from [[http://ieeexplore.ieee.org/|IEEEXplore]] or search in [[http://scholar.google.at/scholar?q=Coordinated+Multi-Robot+Exploration:+Out+of+the+Box+Packages+for+ROS&hl=de&btnG=Suche&lr=|Google Scholar]]. == Running the Node == It's '''VERY IMPORTANT''' that the node always runs with root rights because the protocol is implement using raw sockets requiring root. <
><
>Mark node to automatically run as root by setting the SUID bit:<
> '''sudo chown root adhoc_communication''' <
> '''chmod +s adhoc_communication'''<
> == ROS API == {{{#!clearsilver CS/NodeAPI name = adhoc_communication desc = It's '''VERY IMPORTANT''' that the node always runs with root rights because the protocol is implement using raw sockets requiring root. <
><
>Mark node to automatically run as root by setting the SUID bit:<
> '''sudo chown root adhoc_communication''' <
> '''chmod +s adhoc_communication'''<
> pub { 0.name = /adhoc_communaction/new_robot 0.type = std_msgs/String 0.desc = Publish the name of a new neighbor. 1.name = /adhoc_communaction/remove_robot 1.type = std_msgs/String 1.desc = Publish the name of a neighbor, if the connection to it gets lost. } srv { 0.name = adhoc_communication/send_string 0.type = adhoc_communication/sendString 0.desc = <>Sends a string to a destination robot or multicast group. If the destination dst_robot field is empty a broadcast will be send. Returns true, if string could be send successfully. To send certain types of ROS messages with this service, serialize it with ros::serialization or follow the [[#tutorial|tutorial]]. 1.name = adhoc_communication/get_neighbors 1.type = adhoc_communication/getNeighbors 1.desc = Returns all direct neighbors of the robot. 2.name = adhoc_communication/shut_down 2.type = adhoc_communication/shutDown 2.desc = Quits the node. 3.name = adhoc_communication/broadcast_string 3.type = adhoc_communication/BroadcastString 3.desc = <>Send a multi hop broadcast. The limit field of the request defines how much hops the frame is retransmitted before it will be dropped. 4.name = adhoc_communication/join_mc_group 4.type = adhoc_communication/ChangeMcMembership 4.desc = <>This service allows you to join/leave a multicast group. 5.name = adhoc_communication/get_group_state 5.type = adhoc_communication/GetGroupState 5.desc = Returns information on a specific multicast group. 6.name = adhoc_communication/send_robot_update 6.type = adhoc_communication/SendCMgrRobotUpdate 6.desc = Serializes a message of the type CMgrRobotUpdate and delivers it with the service send_string to the destination. The receiver will deserialize it and publish it on the given topic. 7.name = adhoc_communication/send_auction 7.type = adhoc_communication/SendExpAuction 7.desc = Serializes a message of the type ExpAuction and delivers it with the service [[#send_string|send_string]] to the destination. The receiver will deserialize it and publish it on the given topic. 8.name = adhoc_communication/send_cluster 8.type = adhoc_communication/SendExpCluster 8.desc = Serializes a message of the type ExpCluster and delivers it with the service [[#send_string|send_string]] to the destination. The receiver will deserialize it and publish it on the given topic. 9.name = adhoc_communication/send_frontier 9.type = adhoc_communication/SendExpFrontier 9.desc = Serializes a message of the type ExpFrontier and delivers it with the service [[#send_string|send_string]] to the destination. The receiver will deserialize it and publish it on the given topic. 10.name = adhoc_communication/send_control 10.type = adhoc_communication/SendMmControl 10.desc = Serializes a message of the type MmControl and delivers it with the service [[#send_string|send_string]] to the destination. The receiver will deserialize it and publish it on the given topic. 11.name = adhoc_communication/send_map_update 11.type = adhoc_communication/SendMmMapUpdate 11.desc = Serializes a message of the type MmMapUpdate and delivers it with the service [[#send_string|send_string]] to the destination. The receiver will deserialize it and publish it on the given topic. 12.name = adhoc_communication/send_point 12.type = adhoc_communication/SendMmPoint 12.desc = Serializes a message of the type MmPoint and delivers it with the service [[#send_string|send_string]] to the destination. The receiver will deserialize it and publish it on the given topic. 13.name = adhoc_communication/send_position 13.type = adhoc_communication/SendMmPpsition 13.desc = Serializes a message of the type MmPpsition and delivers it with the service [[#send_string|send_string]] to the destination. The receiver will deserialize it and publish it on the given topic. 14.name = adhoc_communication/send_map 14.type = adhoc_communication/SendOccupancyGrid 14.desc = Serializes a message of the type OccupancyGrid and delivers it with the service [[#send_string|send_string]] to the destination. The receiver will deserialize it and publish it on the given topic. 15.name = adhoc_communication/send_twist 15.type = adhoc_communication/SendTwist 15.desc = Serializes a message of the type Twist and delivers it with the service [[#send_string|send_string]] to the destination. The receiver will deserialize it and publish it on the given topic. 16.name = adhoc_communication/broadcast_robot_update 16.type = adhoc_communication/BroadcastCMgrRobotUpdate 16.desc = Serializes a message of the type CMgrRobotUpdate and delivers it with the service [[#broadcast_string|broadcast_string]] to the destination. The receiver will deserialize it and publish it on the given topic. } param { 0.name = ~interface 0.type = String 0.desc = The using interface for communication. 0.default = wlan0 1.name = ~mac 1.type = String 1.desc = If this parameter will be set, the using interface will have an other mac address than the original hardware address. (e.g: 00:11:00:00:00:00) 1.default = Original hardware address 2.name = ~num_link_retrans 2.type = int 2.desc = The number of retransmissions using time diversity. 2.default = 10 3.name = ~num_e2e_retrans 3.type = int 3.desc = The number of end to end retransmissions using time diversity. 3.default = 10 4.name = ~num_rreq 4.type = int 4.desc = The number tries to find a route to a destination. 4.default = 1 5.name = ~max_frame_size 5.type = int 5.desc = Max size of a ethernet frame. Max size is 1500 Bytes. 5.default = 1500[Bytes] 6.name = ~hop_limit_min 6.type = int 6.desc = todo 6.default = 0 7.name = ~hop_limit_max 7.type = int 7.desc = todo 7.default = 0 8.name = ~hop_limit_increment 8.type = int 8.desc = todo 8.default = 3 9.name = ~robot_name 9.type = String 9.desc = The name of the robot that will be used for the routing. 9.default = Hostname of the robot. 10.name = ~beacon_interval 10.type = int 10.desc = The interval beacons are transmitted. Beacons are used to detect neighbors. 10.default = 250[ms] 11.name = ~max_packet_size 11.type = int 11.desc = Max size of data that can be transmitted. Should not to big because protocol has problems to handle big data transmissions. See [[#bandwith|bandwith]]. 11.default = 10000000[Bytes] 12.name = ~rebuild_mc_tree 12.type = bool 12.desc = Indicates if the multicast group will rebuild recursivly, when connection to uplink is lost. 12.default = false 13.name = ~nack_threshold 13.type = int 13.desc = The threshold value of the packet size when negative acknowleged will be used. 13.default = 10 14.name = ~sim_robot_macs 14.type = String 14.desc = It's possible to limit the robots connectivity by adding a whitelist. The whitelist defines with witch robots the robot can communicate with. The whitelist consists of the hostname and the mac seperated by comma. The single entries are separeted by exclamation marks. Example: "robot_0,00:11:00:00:00:00!robot_2,00:22:00:00:00:00". 14.default = "" 15.name = log_path 15.type = String 15.desc = Path where the node write log files 15.default = "" } }}} <> == Bandwith == As the program doesn't run in the kernel space, it's not that fast as other common network protocols like TCP/IP. The main purpose was to create a node which allows you to exchange data between several roscores and not to create a high speed multimedia exchange protocol. == Send custom ROS messages == Because there is no generic method to deserialize ROS Messages the node is not able to send all type of ROS Messages by default. If you want to send custom message with the adhoc_communcation node you either must serialize/deserialze the message in your code or extend my node to provide a service to send a custom message. === How to serialize messages in you code === To send custom messages you just need to serialize a message to a string and then send it with the service [[#send_string|send_string]]. To serialize any type of ROS message you can use this function: {{{ template std::string getSerializedMessage(t message) { /* Description: * returns a serialized ROS message as string to send it over network. */ uint32_t serial_size = ros::serialization::serializationLength(message); boost::shared_array buffer(new uint8_t[serial_size]); ros::serialization::OStream streamOut(buffer.get(), serial_size); ros::serialization::serialize(streamOut, message); std::string serialized_map = ""; serialized_map.append((const char*) buffer.get(), serial_size); return serialized_map; } }}} On the receiver side you need to listen on the topic you serialized message will be published and deserialize it back to an object. Following function will allow you to deserialize any type of ROS messages. {{{ template void desializeObject(unsigned char* serialized_message, uint32_t length, t * obj) { /* Description: * de-serialize a ROS message from a buffer. */ try { ros::serialization::IStream stream(serialized_message, length); ros::serialization::deserialize(stream, *obj); } catch (ros::serialization::StreamOverrunException e) { ROS_ERROR("IN desializeObject: NODE THROWS EXCEPTION: %s ", e.what()); ROS_ERROR("PARAMETERS: length=[%u] object type=[%s]", length, typeid (*obj).name()); } } }}} <> === How to add a service to send a custom message === In this tutorial you will learn how to extend the adhoc_communcation node by implementing a new service allowing to send your own ROS message. In this tutorial a service that is able to send messages of the type geometry_msgs::Quaternion will be implemented, but you can choose any other ROS message when you work through this tutorial. NOTE: The code to adapt is marked with the tag /*Tutorial*/ in the screen shots. ==== Step 1 - Define Payload ==== '''File: defines.h''' Define the payload type of the frame. This value must be unique w.r.t. to all payload types. {{attachment:step_1.png||width="730px"}} ==== Step 2 - Add a new service definition in the package ==== '''Folder''': srv '''File''': sendQuaternion.srv '''File content''':''' ''' {{{ string topic geometry_msgs/Quaternion Quaternion string destinationHost --- uint8 successfullySend }}} Include the service in '''header.h''' {{{ #include "mapExchange/sendQuaternion.h" }}} ==== Step 3 - Implementation ==== '''File''': ad_hoc_communication.cpp Implement the function for the service call. Add the function to the other service calls. In this case call the function 'send Quaternion'. The parameter of the functions are a service request and a service response of the service that was created in Step 2. {{attachment:step_3_1.png||width="730px"}} Advertise the Service. Function: ''main()'' Service name is ''send_quaternion''. {{attachment:step_3_2.png||width="730px"}} ==== Step 4 - Implementation II ==== Create a function to create a quaternion from the serialization string. {{attachment:step_4.png||width="730px"}} ==== Step 5 - Implementation III ==== '''File''': ad_hoc_communication.cpp '''Function''': publishPacket Adapt the function ''publishPacket'' that the new payload type will be published. To deserialize the message, the function from Step 4 is used. {{attachment:step_5.png||width="730px"}}