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 #ifndef SHORTHEAVYLOADER_HPP
00021 #define SHORTHEAVYLOADER_HPP
00022
00023 #include <iostream>
00024
00025 #include <boost/thread/mutex.hpp>
00026
00027 #include <ros/ros.h>
00028 #include <std_msgs/UInt8.h>
00029
00030 #include <socrob/multicast.h>
00031
00032
00033
00034 using namespace std;
00035 using namespace ros;
00036 using namespace socrob::multicast;
00037
00038
00039
00040 class ShortHeavyLoader
00041 {
00042 int sid_;
00043
00044 const uint8_t MAGIC_BYTE_;
00045
00046 unsigned long rounds_;
00047
00048 public:
00049 ShortHeavyLoader (int sid) :
00050 sid_ (sid),
00051 MAGIC_BYTE_ (0),
00052 rounds_ (0) {}
00053
00054
00055
00056 bool
00057 is_question (vector<uint8_t> & question) {
00058 std_msgs::UInt8 magic_msg;
00059 deserialize (magic_msg, question);
00060
00061 if (magic_msg.data == MAGIC_BYTE_) {
00062 return true;
00063 }
00064
00065 return false;
00066 }
00067
00068
00069
00070 void
00071 short_handler (vector<uint8_t>& answer,
00072 id_type from,
00073 vector<uint8_t> const& question) {
00074 }
00075
00076
00077
00078 void
00079 short_callback (std::map<id_type, std::vector<uint8_t> > const& answers) {
00080 }
00081
00082
00083
00084 void
00085 timer (socrob::multicast::Manager& manager) {
00086 vector<uint8_t> question = vector<uint8_t> (1);
00087 question[0] = 0;
00088
00089 for (int i = 0; i < 1000; i++) {
00090 set<id_type> required_sids;
00091 required_sids.insert (0);
00092 required_sids.insert (1);
00093 required_sids.insert (2);
00094 required_sids.insert (3);
00095 required_sids.insert (4);
00096
00097 if (manager.startShortRound (question, required_sids, boost::bind (&ShortHeavyLoader::short_callback, this, _1))) {
00098 rounds_++;
00099 }
00100 }
00101 }
00102
00103
00104
00105 void
00106 statistics() {
00107 cout << "ShortHeavyLoader at " << sid_ << " successfully started " << rounds_ << " short rounds." << endl;
00108 }
00109 };
00110
00111 #endif