Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020 #include <iostream>
00021
00022 #include <ros/console.h>
00023
00024 #include <socrob/multicast.h>
00025
00026 #include "TestShortSingleDelay.h"
00027 #include "ShortHeavyLoader.h"
00028
00029
00030
00031 using namespace std;
00032 using namespace ros;
00033 using namespace socrob::multicast;
00034
00035
00036
00037 void
00038 short_handler (TestShortSingleDelay& test_short,
00039 ShortHeavyLoader& heavy_loader,
00040 vector<uint8_t>& answer,
00041 id_type from,
00042 vector<uint8_t> & question)
00043 {
00044 if (test_short.is_question (question)) {
00045 test_short.short_handler (answer, from, question);
00046 }
00047 else if (heavy_loader.is_question (question)) {
00048 heavy_loader.short_handler (answer, from, question);
00049 }
00050 else {
00051 ROS_FATAL ("Neither tester nor loader claimed the question");
00052 abort();
00053 }
00054 }
00055
00056
00057
00058 int main (int argc, char** argv)
00059 {
00060 init (argc, argv, "short_single_delay_heavy");
00061
00062 ros::NodeHandle nh;
00063
00064 int sid;
00065 if (! ros::param::getCached ("robot_number", sid)) {
00066 ROS_FATAL ("Could not get robot_number param");
00067 abort();
00068 }
00069 sid -= 1;
00070
00071 TestShortSingleDelay test_short (sid, "Heavy");
00072 ShortHeavyLoader heavy_loader (sid);
00073
00074 {
00075 Manager srmm (ManagerOptions (sid, 5, "239.255.1.1")
00076 .bandwidth_bps (57671)
00077 .ports (2000, 2001)
00078 .tup_ms (100)
00079 .short_handler (boost::bind (&short_handler, boost::ref (test_short), boost::ref (heavy_loader), _1, _2, _3)));
00080
00081 ros::Rate loop_rate (10);
00082 while (ros::ok()) {
00083 test_short.timer (srmm);
00084 heavy_loader.timer (srmm);
00085 loop_rate.sleep();
00086 }
00087 }
00088
00089 test_short.statistics();
00090 heavy_loader.statistics();
00091 }