RoutedFrame.cpp
Go to the documentation of this file.
00001 
00002 /*
00003  * RoutedFrame.cpp
00004  *
00005  *  Created on: 29.07.2013
00006  *      Author: Günther Cwioro
00007  *
00008  *
00009  * Structure of a routed frame looks like:
00010  *
00011  * Destination MAC      // ff:ff:ff:ff:ff:ff or "real" destination. Depends on CR                       6Byte
00012  * SOURCE MAC           // MAC of the using interface                                                                           6Byte
00013  * ETH_TYPE_FIELD       // 0x4148 (AH as string)                                                                                        2Byte
00014  * FRAME_TYPE           // 0x64 (d as string)                                                                                           1Byte
00015  * DESTINATION          // destination mac                                                                                                      6Byte
00016  * FRAME ID                     // id of frame                                                                                                          4Byte
00017  * ROUTE ID                                                                                                                                                             4Byte
00018  * PACKET ID                                                                                                                                                    4Byte
00019  * SEQUENCE NUMBER                                                                                                                                              4Byte
00020  * PACKET SIZE                                                                                                                                                  4Byte
00021  * SOURCE HOST Length                                                                                                                                   4Byte
00022  * SOURCE HOST                                                                                                                                                  VAR
00023  * MC GROUP LENGTH                                                                                                                                              4Byte
00024  * MC GROUP NAME                                                                                                                                                VAR
00025  * TOPIC_LENGTH                                                                                                                                                 4Byte
00026  * TOPIC                        // topic that the payload will be published later                                       VAR
00027  * PAYLOAD TYPE     // this field is used to distinguish different payload types                1Byte
00028  * PAYLOAD_LENGTH                                                                                                                                               4Byte
00029  * PAYLOAD                      // payload                                                                                                                      VAR
00030  * FLAG FIELD  // cr_flag, mc_flag, pos_ack, neg_ack
00031  * CRC CHECKSUM                                                                                                                                                 4Byte
00032  *
00033  *      How the frame is delivered:
00034  *
00035  *      NW:     (S) - (N1) - (D)
00036  *
00037  *      t(0)    (S)  data->   (N1)            (D)
00038  *      t(1)             <-ack
00039  *      t(2)                                            data->
00040  *      t(3)                                            <-ack
00041  *      t(4)                                            <-ACK
00042  *      t(5)                                            ack->
00043  *      t(6)             <-ACK
00044  *      t(7)             ack->
00045  *
00046  *      To send a packet, of course its necessary that there is a route for the destination in the routing table.
00047  *
00048  *      1) Source send the frame to N1
00049  *      2) N1 receive the frame and sends a ack to the S. N1 looks in his routing table wich is the next host mac and send it to the D
00050  *      3) the D gets the frame and also sends an ack to N1.
00051  */
00052 
00053 #include <string>
00054 
00055 #include "RoutedFrame.h"
00056 #include "EthernetFrame.h"
00057 
00058 RoutedFrame::RoutedFrame(std::string topic_to_publish, std::string data,
00059                          uint8_t payload_type_field, uint32_t pack_id,
00060                          uint32_t pack_sequence_num, uint32_t frames_in_pack)
00061 {
00062 
00063     this->payload_ = data;
00064     this->header_.payload_type = payload_type_field;
00065     this->topic_ = topic_to_publish;
00066     header_.frame_id = frame_count_stat;
00067     this->header_.packet_id = pack_id;
00068     header_.packet_sequence_num = pack_sequence_num;
00069     header_.packet_size = frames_in_pack;
00070     frame_count_stat++;
00071     cr_flag = false;
00072     mc_g_name_ = "";
00073     this->mc_flag = false;
00074     this->negative_ack_type = false;
00075 
00076     this->resend_flag = false;
00077     this->header_.frame_type = FRAME_TYPE_TRANSPORT_DATA;
00078 
00079 
00080 
00081 }
00082 
00083 RoutedFrame::RoutedFrame()
00084 {
00085 
00086 }
00087 
00088 unsigned long RoutedFrame::getSize()
00089 {
00090     unsigned long size = 0;
00091     size += this->payload_.size();
00092     size += RoutedFrame::HEADER_FIXED_LEN;
00093     return size;
00094 }
00095 
00096 RoutedFrame::RoutedFrame(unsigned char* buffer)
00097 {
00098     unsigned char* buffer_start = buffer;
00099     buffer_str_len_ = 0;
00100 
00101     /*ETHERNET HEADER*/
00102     eh_header* eh = (struct eh_header *) buffer;
00103     buffer += sizeof (eh_header);
00104     buffer_str_len_ += sizeof (eh_header);
00105 
00106     /*FRAME HEADER*/
00107     rf_header* rfh = (struct rf_header *) buffer;
00108     buffer += sizeof (rf_header);
00109     buffer_str_len_ += sizeof (rf_header);
00110 
00111     /*SOURCE HOST*/
00112     hostname_source_ = "";
00113     hostname_source_.append((const char*) buffer, rfh->hostname_source_len);
00114     buffer += rfh->hostname_source_len;
00115     buffer_str_len_ += rfh->hostname_source_len;
00116 
00117 
00118 
00119     /*MC GROUP */
00120     mc_g_name_ = "";
00121     if (rfh->mc_group_len > 0)
00122     {
00123         mc_g_name_.append((const char*) buffer, rfh->mc_group_len);
00124         buffer += rfh->mc_group_len;
00125         buffer_str_len_ += rfh->mc_group_len;
00126     }
00127 
00128 
00129     /*TOPIC*/
00130     topic_ = "";
00131     topic_.append((const char*) buffer, rfh->topic_len);
00132     buffer += rfh->topic_len;
00133     buffer_str_len_ += rfh->topic_len;
00134 
00135 
00136     /*PAYLOAD*/
00137     payload_ = "";
00138     payload_.append((const char*) buffer, rfh->payload_len);
00139     buffer += rfh->payload_len;
00140     buffer_str_len_ += rfh->payload_len;
00141 
00142     /*INIT FLAGS*/
00143     cr_flag = (rfh->flag_field / 128) % 2 == 1;
00144     mc_flag = (rfh->flag_field / 64) % 2 == 1;
00145     negative_ack_type = (rfh->flag_field / 32) % 2 == 1;
00146     resend_flag = (rfh->flag_field / 16) % 2 == 1;
00147 
00148     /*CRC */
00149     uint32_t crc = 0;
00150     memcpy((unsigned char*) &crc, (unsigned char*) buffer, 4); // get CRC
00151 
00152     std::string crc_data_string = "";
00153     crc_data_string.append((const char*) buffer_start,
00154                            this->HEADER_FIXED_LEN + rfh->hostname_source_len + rfh->mc_group_len + rfh->topic_len + rfh->payload_len);
00155     correct_crc_ = (crc == (uint32_t) GetCrc32(crc_data_string));
00156 
00157 
00158 
00159     /* COPY HEADER FIELDS */
00160     memcpy(&this->eh_h_, &(*eh), sizeof (eh_header));
00161     memcpy(&this->header_, &(*rfh), sizeof (rf_header));
00162 
00163 }
00164 
00165 RoutedFrame::~RoutedFrame()
00166 {
00167     // TODO Auto-generated destructor stub
00168 }
00169 
00170 std::string RoutedFrame::getFrameAsNetworkString(uint32_t route_id, unsigned char next_hop[6], string source_host, unsigned char source[6])
00171 {
00172     memcpy(this->eh_h_.eh_source, source, ETH_ALEN);
00173     memcpy(&this->header_.mac_destination_, next_hop, ETH_ALEN);
00174 
00175 
00176     this->hostname_source_ = source_host;
00177 
00178     if (this->enable_cooperative_relaying)
00179         memcpy((void *) eh_h_.eh_dest, (void*) bcast_mac, ETH_ALEN);
00180     else
00181         memcpy((void *) eh_h_.eh_dest, (void*) next_hop, ETH_ALEN);
00182     this->header_.route_id = route_id;
00183 
00184 
00185     /*FLAG FIELD*/
00186     this->header_.flag_field = 0;
00187     if (cr_flag)
00188         this->header_.flag_field += 128;
00189     if (mc_flag)
00190         this->header_.flag_field += 64;
00191     if (negative_ack_type)
00192         this->header_.flag_field += 32;
00193     if (resend_flag)
00194         this->header_.flag_field += 16;
00195 
00196     /*LEN FIELDS */
00197     this->header_.hostname_source_len = hostname_source_.length();
00198     this->header_.mc_group_len = mc_g_name_.length();
00199     this->header_.topic_len = topic_.length();
00200     this->header_.payload_len = payload_.length();
00201 
00202 
00203 
00204 
00205     unsigned char f_buffer[ETHER_MAX_LEN]; // = unsigned char[ETHER_MAX_LEN];
00206     unsigned char* buffer = f_buffer;
00207     unsigned char* buffer_start = f_buffer;
00208 
00209 
00210 
00211     /*ETHERNET FIELDS*/
00212     //eh_header* eh = (struct eh_header *) buffer;
00213     memcpy(buffer, &this->eh_h_, sizeof (eh_header));
00214     buffer += sizeof (eh_header);
00215 
00216     /*FIXED RF HEADER FIELDS*/
00217     memcpy(buffer, &this->header_, sizeof (rf_header));
00218     buffer += sizeof (rf_header);
00219 
00220     /*SOURCE HOST */
00221     memcpy(buffer, this->hostname_source_.data(),
00222            this->hostname_source_.length());
00223     buffer += this->hostname_source_.length();
00224 
00225     /*MC GROUP */
00226     memcpy(buffer, this->mc_g_name_.data(), this->mc_g_name_.length());
00227     buffer += mc_g_name_.length();
00228 
00229     /*TOPIC*/
00230     memcpy(buffer, this->topic_.data(), this->topic_.length());
00231     buffer += topic_.length();
00232 
00233 
00234     /*PAYLOAD */
00235     memcpy(buffer, this->payload_.data(), this->payload_.length());
00236     buffer += payload_.length();
00237 
00238 
00239     /*CRC*/
00240     uint32_t dynamic_field_len = this->hostname_source_.length() + this->mc_g_name_.length() + topic_.length() + payload_.length();
00241     std::string crc_string = std::string((const char*) buffer_start, this->HEADER_FIXED_LEN + dynamic_field_len);
00242     uint32_t crc = GetCrc32(crc_string);
00243     memcpy(buffer, &crc, sizeof (uint32_t));
00244     buffer += sizeof (uint32_t);
00245 
00246 
00247     return string((const char*) buffer_start, this->HEADER_FIXED_LEN + dynamic_field_len + sizeof (uint32_t));
00248 
00249 }
00250 
00251 std::string RoutedFrame::getFrameAsNetworkString(routing_entry r, unsigned char src[6])
00252 {
00253     return this->getFrameAsNetworkString(r.id, r.next_hop, r.hostname_source, src);
00254 }
00255 
00256 stc_frame RoutedFrame::getFrameStruct()
00257 {
00258     stc_frame stc;
00259     stc.type = header_.frame_type;
00260     stc.frame_id = header_.frame_id;
00261     memcpy(stc.mac, header_.mac_destination_, ETH_ALEN);
00262     stc.mc_group = mc_g_name_;
00263     stc.hostname_source = hostname_source_;
00264 
00265     stc.retransmitted = 0;
00266 
00267     return stc;
00268 }
00269 
00270 


adhoc_communication
Author(s): Guenter Cwioro , Torsten Andre
autogenerated on Thu Aug 27 2015 11:56:40