Main file for the ad hoc communication node including the main function. More...
#include "header.h"
Go to the source code of this file.
Functions | |
void | checkMutexAvailability (boost::mutex *m, string name) |
void | deleteObsoleteRequests () |
void | deleteOldPackets () |
void | deliverMcAckFrame (stc_RoutedFrame &stc_rf, routing_entry &r, bool send_ack) |
bool | getGroupStateF (adhoc_communication::GetGroupState::Request &req, adhoc_communication::GetGroupState::Response &res) |
McPosAckObj * | getMcAckObj (std::string *group, uint32_t p_id, uint32_t seq) |
bool | getNeighbors (adhoc_communication::GetNeighbors::Request &req, adhoc_communication::GetNeighbors::Response &res) |
bool | gotAck (AckLinkFrame *inc_frame) |
bool | gotAckRoutedFrame (routing_entry &route) |
bool | joinMCGroup (adhoc_communication::ChangeMCMembership::Request &req, adhoc_communication::ChangeMCMembership::Response &res) |
Service to tell the node to attempt to connect to a multicast group. | |
int | main (int argc, char **argv) |
void | processAckRoutedFrame (AckRoutedFrame *in_a_rf) |
void | processBeacon (Beacon *beacon) |
void | processBroadcastFrame (RoutedFrame *f) |
void | processIncomingFrames () |
void | processMcAckFrame (McAckFrame *f) |
void | processMcActivationFrame (McRouteActivationFrame *f) |
void | processRoutedFrame (RoutedFrame *f) |
void | processRouteRequest (RouteRequest req) |
void | processRouteResponse (RouteResponse rr) |
template<class message > | |
void | publishMessage (message m, string topic) |
void | publishPacket (Packet *p) |
void | receiveFrames () |
void | resendLinkFrame (stc_frame f) |
void | resendMcFrame (boost::condition_variable &condi, stc_RoutedFrame *rf, routing_entry route) |
void | resendRoutedFrame (boost::condition_variable &condi, routing_entry route) |
void | resendRouteRequest (route_request &req, boost::condition_variable &con) |
bool | sendAuction (adhoc_communication::SendExpAuction::Request &req, adhoc_communication::SendExpAuction::Response &res) |
void | sendBeacons () |
bool | sendBroadcast (string &topic, string &data, uint8_t type, uint16_t range) |
bool | sendBroadcastCMgrRobotUpdate (adhoc_communication::BroadcastCMgrRobotUpdate::Request &req, adhoc_communication::BroadcastCMgrRobotUpdate::Response &res) |
bool | sendBroadcastString (adhoc_communication::BroadcastString::Request &req, adhoc_communication::BroadcastString::Response &res) |
bool | sendCluster (adhoc_communication::SendExpCluster::Request &req, adhoc_communication::SendExpCluster::Response &res) |
bool | sendControlMessage (adhoc_communication::SendMmControl::Request &req, adhoc_communication::SendMmControl::Response &res) |
bool | sendFrontier (adhoc_communication::SendExpFrontier::Request &req, adhoc_communication::SendExpFrontier::Response &res) |
void | sendLinkAck (unsigned char *dest, unsigned char *confirmer_mac, uint32_t id, string source, bool cr, uint8_t type) |
bool | sendMap (adhoc_communication::SendOccupancyGrid::Request &req, adhoc_communication::SendOccupancyGrid::Response &res) |
bool | sendMapUpdate (adhoc_communication::SendMmMapUpdate::Request &req, adhoc_communication::SendMmMapUpdate::Response &res) |
void | sendMcAck (unsigned char *dst, string h_source, string g_name, uint32_t packet_id, uint32_t seq_num) |
bool | sendPacket (std::string &hostname_destination, std::string &payload, uint8_t data_type_, std::string &topic) |
bool | sendPoint (adhoc_communication::SendMmPoint::Request &req, adhoc_communication::SendMmPoint::Response &res) |
bool | sendPosition (adhoc_communication::SendMmRobotPosition::Request &req, adhoc_communication::SendMmRobotPosition::Response &res) |
bool | sendQuaternion (adhoc_communication::SendQuaternion::Request &req, adhoc_communication::SendQuaternion::Response &res) |
bool | sendRobotUpdate (adhoc_communication::SendCMgrRobotUpdate::Request &req, adhoc_communication::SendCMgrRobotUpdate::Response &res) |
bool | sendRouteRequest (string *dst, routing_entry *route) |
bool | sendString (adhoc_communication::SendString::Request &req, adhoc_communication::SendString::Response &res) |
bool | sendTwist (adhoc_communication::SendTwist::Request &req, adhoc_communication::SendTwist::Response &res) |
void | shutDown () |
Shuts down the rode node. | |
bool | shutDownRos (adhoc_communication::ShutDown::Request &req, adhoc_communication::ShutDown::Response &res) |
Main file for the ad hoc communication node including the main function.
Node instruction:
The node advertise three services: 1) name: send_string type: sendString This service is to send any data in form from a string over the network. Publish type: getData
2) name: send_map type: sendOccupancyGrid This service sends serialized ROS messages Publish type: nav_msgs/OccupancyGrid
3) name: send_position type: sendPosition This service sends serialized ROS messages Publish type: positionExchange
Every service request has a field for the hostname of the destination and a field for the topic to publish the message. If you want to broadcast a message you must set the destination hostname as an empty string. NOTE: Broadcast don't include acknowledgments and can only be send to direct neighbors and if just one frame of the broadcast packet will be lost over transmission, the whole packet is useless.
The node 'communication_tester' of this package demonstrate how you can use the services. There is also a tutorial to adapt this node to implement a service to send your own ROS messages.
The node have a lot of parameter and defines that can be changed. There is a list of all parameters and defines in the docu foldere.
Special Notes: (not important for users)
For debugging reasons there is an option to set the hostname and the mac of the node manually. There is also the opportunity to give the node only a few of reachable hosts. These option can be set when you start the node. Here an example:
I want to start a node with hostname "my_hostname" and the mac "84:a6:c8:43:1e:3a". The node should only be able to reach two hosts: neighbor_one 10:00:00:00:00:00 neighbor_two 20:00:00:00:00:00 To reach this you must start the node like this:
rosrun ad_hoc_comm ad_hoc_communication wlan0 my_hostname 84:a6:c8:43:1e:3a neighbor_one 10:00:00:00:00:00 neighbor_two 20:00:00:00:00:00
NOTE: If you don't use this feature you can start the node normally and all reachable neighbor will be detected automatically. If you want to use this feature, make sure DEBUG is defined.
Definition in file adhoc_communication.cpp.
void checkMutexAvailability | ( | boost::mutex * | m, |
string | name | ||
) |
Definition at line 1026 of file adhoc_communication.cpp.
void deleteObsoleteRequests | ( | ) |
Definition at line 3302 of file adhoc_communication.cpp.
void deleteOldPackets | ( | ) |
Definition at line 3332 of file adhoc_communication.cpp.
void deliverMcAckFrame | ( | stc_RoutedFrame & | stc_rf, |
routing_entry & | r, | ||
bool | send_ack | ||
) |
Definition at line 2035 of file adhoc_communication.cpp.
bool getGroupStateF | ( | adhoc_communication::GetGroupState::Request & | req, |
adhoc_communication::GetGroupState::Response & | res | ||
) |
Definition at line 53 of file adhoc_communication.cpp.
McPosAckObj* getMcAckObj | ( | std::string * | group, |
uint32_t | p_id, | ||
uint32_t | seq | ||
) |
Definition at line 1725 of file adhoc_communication.cpp.
bool getNeighbors | ( | adhoc_communication::GetNeighbors::Request & | req, |
adhoc_communication::GetNeighbors::Response & | res | ||
) |
Definition at line 326 of file adhoc_communication.cpp.
bool gotAck | ( | AckLinkFrame * | inc_frame | ) |
Definition at line 1247 of file adhoc_communication.cpp.
bool gotAckRoutedFrame | ( | routing_entry & | route | ) |
Definition at line 684 of file adhoc_communication.cpp.
bool joinMCGroup | ( | adhoc_communication::ChangeMCMembership::Request & | req, |
adhoc_communication::ChangeMCMembership::Response & | res | ||
) |
Service to tell the node to attempt to connect to a multicast group.
[in] | req | The service request object. |
[out] | res | The service response object. |
Implements the ROS service join_mc_group to tell a node to connect to a multicast group.
Definition at line 108 of file adhoc_communication.cpp.
int main | ( | int | argc, |
char ** | argv | ||
) |
Definition at line 1039 of file adhoc_communication.cpp.
void processAckRoutedFrame | ( | AckRoutedFrame * | in_a_rf | ) |
Definition at line 1790 of file adhoc_communication.cpp.
void processBeacon | ( | Beacon * | beacon | ) |
Definition at line 2646 of file adhoc_communication.cpp.
void processBroadcastFrame | ( | RoutedFrame * | f | ) |
Definition at line 2072 of file adhoc_communication.cpp.
void processIncomingFrames | ( | ) |
Definition at line 2794 of file adhoc_communication.cpp.
void processMcAckFrame | ( | McAckFrame * | f | ) |
Definition at line 1754 of file adhoc_communication.cpp.
void processMcActivationFrame | ( | McRouteActivationFrame * | f | ) |
Definition at line 2700 of file adhoc_communication.cpp.
void processRoutedFrame | ( | RoutedFrame * | f | ) |
Definition at line 1898 of file adhoc_communication.cpp.
void processRouteRequest | ( | RouteRequest | req | ) |
Definition at line 2252 of file adhoc_communication.cpp.
void processRouteResponse | ( | RouteResponse | rr | ) |
Definition at line 2481 of file adhoc_communication.cpp.
void publishMessage | ( | message | m, |
string | topic | ||
) |
Definition at line 1628 of file adhoc_communication.cpp.
void publishPacket | ( | Packet * | p | ) |
Definition at line 2994 of file adhoc_communication.cpp.
void receiveFrames | ( | ) |
Definition at line 1330 of file adhoc_communication.cpp.
void resendLinkFrame | ( | stc_frame | f | ) |
Definition at line 3380 of file adhoc_communication.cpp.
void resendMcFrame | ( | boost::condition_variable & | condi, |
stc_RoutedFrame * | rf, | ||
routing_entry | route | ||
) |
Definition at line 3273 of file adhoc_communication.cpp.
void resendRoutedFrame | ( | boost::condition_variable & | condi, |
routing_entry | route | ||
) |
Definition at line 3218 of file adhoc_communication.cpp.
void resendRouteRequest | ( | route_request & | req, |
boost::condition_variable & | con | ||
) |
Definition at line 3155 of file adhoc_communication.cpp.
bool sendAuction | ( | adhoc_communication::SendExpAuction::Request & | req, |
adhoc_communication::SendExpAuction::Response & | res | ||
) |
Definition at line 495 of file adhoc_communication.cpp.
void sendBeacons | ( | ) |
Definition at line 1662 of file adhoc_communication.cpp.
bool sendBroadcast | ( | string & | topic, |
string & | data, | ||
uint8_t | type, | ||
uint16_t | range | ||
) |
Definition at line 385 of file adhoc_communication.cpp.
bool sendBroadcastCMgrRobotUpdate | ( | adhoc_communication::BroadcastCMgrRobotUpdate::Request & | req, |
adhoc_communication::BroadcastCMgrRobotUpdate::Response & | res | ||
) |
Definition at line 418 of file adhoc_communication.cpp.
bool sendBroadcastString | ( | adhoc_communication::BroadcastString::Request & | req, |
adhoc_communication::BroadcastString::Response & | res | ||
) |
Definition at line 397 of file adhoc_communication.cpp.
bool sendCluster | ( | adhoc_communication::SendExpCluster::Request & | req, |
adhoc_communication::SendExpCluster::Response & | res | ||
) |
Definition at line 515 of file adhoc_communication.cpp.
bool sendControlMessage | ( | adhoc_communication::SendMmControl::Request & | req, |
adhoc_communication::SendMmControl::Response & | res | ||
) |
Definition at line 576 of file adhoc_communication.cpp.
bool sendFrontier | ( | adhoc_communication::SendExpFrontier::Request & | req, |
adhoc_communication::SendExpFrontier::Response & | res | ||
) |
Definition at line 613 of file adhoc_communication.cpp.
void sendLinkAck | ( | unsigned char * | dest, |
unsigned char * | confirmer_mac, | ||
uint32_t | id, | ||
string | source, | ||
bool | cr, | ||
uint8_t | type | ||
) |
Definition at line 1739 of file adhoc_communication.cpp.
bool sendMap | ( | adhoc_communication::SendOccupancyGrid::Request & | req, |
adhoc_communication::SendOccupancyGrid::Response & | res | ||
) |
Definition at line 366 of file adhoc_communication.cpp.
bool sendMapUpdate | ( | adhoc_communication::SendMmMapUpdate::Request & | req, |
adhoc_communication::SendMmMapUpdate::Response & | res | ||
) |
Definition at line 594 of file adhoc_communication.cpp.
void sendMcAck | ( | unsigned char * | dst, |
string | h_source, | ||
string | g_name, | ||
uint32_t | packet_id, | ||
uint32_t | seq_num | ||
) |
Definition at line 2021 of file adhoc_communication.cpp.
bool sendPacket | ( | std::string & | hostname_destination, |
std::string & | payload, | ||
uint8_t | data_type_, | ||
std::string & | topic | ||
) |
bool sendPoint | ( | adhoc_communication::SendMmPoint::Request & | req, |
adhoc_communication::SendMmPoint::Response & | res | ||
) |
Definition at line 556 of file adhoc_communication.cpp.
bool sendPosition | ( | adhoc_communication::SendMmRobotPosition::Request & | req, |
adhoc_communication::SendMmRobotPosition::Response & | res | ||
) |
Definition at line 476 of file adhoc_communication.cpp.
bool sendQuaternion | ( | adhoc_communication::SendQuaternion::Request & | req, |
adhoc_communication::SendQuaternion::Response & | res | ||
) |
Definition at line 345 of file adhoc_communication.cpp.
bool sendRobotUpdate | ( | adhoc_communication::SendCMgrRobotUpdate::Request & | req, |
adhoc_communication::SendCMgrRobotUpdate::Response & | res | ||
) |
Definition at line 439 of file adhoc_communication.cpp.
bool sendRouteRequest | ( | string * | dst, |
routing_entry * | route | ||
) |
Definition at line 634 of file adhoc_communication.cpp.
bool sendString | ( | adhoc_communication::SendString::Request & | req, |
adhoc_communication::SendString::Response & | res | ||
) |
Definition at line 535 of file adhoc_communication.cpp.
bool sendTwist | ( | adhoc_communication::SendTwist::Request & | req, |
adhoc_communication::SendTwist::Response & | res | ||
) |
Definition at line 458 of file adhoc_communication.cpp.
void shutDown | ( | ) |
Shuts down the rode node.
Definition at line 89 of file adhoc_communication.cpp.
bool shutDownRos | ( | adhoc_communication::ShutDown::Request & | req, |
adhoc_communication::ShutDown::Response & | res | ||
) |
Definition at line 95 of file adhoc_communication.cpp.