00001
00002
00003
00004
00005
00006
00007
00008 #ifndef LOGGING_H
00009 #define LOGGING_H
00010
00011 #include "Logging.h"
00012 #include "ros/ros.h"
00013 #include "structs.h"
00014 #include "functions.h"
00015 #include <boost/filesystem.hpp>
00016
00017 class Logging
00018 {
00019
00020
00021 public:
00022 Logging();
00023 Logging(const Logging& orig);
00024 static void init(ros::NodeHandle* n, std::string* robot_name);
00025
00026 static void log();
00027 static bool createLogPath();
00028 static void periodicLog(unsigned long interval_ms);
00029 static void logServiceCalls(string service_name, unsigned long time_call, unsigned long time_res, unsigned long size, bool ret_val);
00030 static void logUcPacketsSummary(unsigned long interval_ms);
00031 static void logMcPacketsSummary(unsigned long interval_ms);
00032 static void logMemoryConsumptionPackets(unsigned long interval_ms, boost::mutex* mtx_pack, list<Packet>* packets, boost::mutex* mtx_cached_mc, list<Packet>* cached_mc, boost::mutex* mtx_unack_link_frames, list<stc_frame>* unack_link_frames, boost::mutex* mtx_unack_cr_frames, list<ack_cr_info>* unack_cr_frames);
00033 static void logRoutingTable(std::list<routing_entry>* u_entries, std::list<McTree*>* m_entries);
00034 static void logRRequestInitiater(route_request* req, routing_entry* route);
00035 static void logRRequestIntermediate(RouteRequest* r);
00036 static void logTransportFrame(stc_RoutedFrame* f, routing_entry* route, unsigned long start_time, unsigned long end_time, bool success);
00037 static void logUcLinkTransmission(stc_frame f);
00038 static void logRRequestReceiver(std::string h_src, uint32_t id, uint16_t counter, uint16_t hobs, bool selected, std::list<mac> path_l);
00039
00040 static void createLogFile(std::list<std::string>* table, std::string* filename);
00041 static void safeLogs();
00042
00043 static uint32_t getProperty(std::string prog_name);
00044 static void increaseProperty(std::string prop_name);
00045 static void increaseProperty(std::string prop_name, uint32_t value);
00046 static void decreaseProperty(std::string prop_name);
00047 static void decreaseProperty(std::string prop_name, uint32_t value);
00048
00049 static ros::NodeHandle* n;
00050
00051 static boost::mutex mtx_logging;
00052
00053 static std::map<std::string, uint32_t> uint32_properties;
00054
00055
00056
00057 static std::list<std::string> entries_r_table, entries_rreq_initi, entries_rreq_recv, entries_rreq_interm, entries_mem_consumption, entries_uc_frames, entries_mc_frames, entries_link_frames, entries_service_calls, entries_transport_frames;
00058 static std::string log_path, routing_table_file, route_req_src_file, route_req_dst_file, route_req_iterm_file, mem_consumption_file, uc_frames_file, mc_frames_file, link_frames_file, sercice_calls_file, transport_frames_file;
00059 static std::string* robot_name;
00060
00061
00062 virtual ~Logging();
00063 private:
00064 static bool removeRouteRequestReceiver(RouteResponse* res);
00065
00066 };
00067 ros::NodeHandle* Logging::n = NULL;
00068 std::list<std::string> Logging::entries_r_table;
00069 std::list<std::string> Logging::entries_rreq_initi;
00070 std::list<std::string> Logging::entries_rreq_interm;
00071 std::list<std::string> Logging::entries_rreq_recv;
00072 std::list<std::string> Logging::entries_mem_consumption;
00073 std::list<std::string> Logging::entries_uc_frames;
00074 std::list<std::string> Logging::entries_mc_frames;
00075 std::list<std::string> Logging::entries_link_frames;
00076 std::list<std::string> Logging::entries_service_calls;
00077 std::list<std::string> Logging::entries_transport_frames;
00078
00079
00080 std::map<std::string, uint32_t> Logging::uint32_properties;
00081
00082 std::string Logging::log_path = "";
00083 std::string* Logging::robot_name = NULL;
00084
00085 std::string Logging::routing_table_file = "routing_table.csv";
00086 std::string Logging::route_req_src_file = "rreq_initiater.csv";
00087 std::string Logging::route_req_dst_file = "rreq_receiver.csv";
00088 std::string Logging::route_req_iterm_file = "rreq_intermediate.csv";
00089 std::string Logging::mem_consumption_file = "packet_memory_consumption.csv";
00090 std::string Logging::uc_frames_file = "unicast_datalink_transmission_summary.csv";
00091 std::string Logging::mc_frames_file = "multicast.csv";
00092 std::string Logging::link_frames_file = "unicast_link_transmission.csv";
00093 std::string Logging::sercice_calls_file = "services.csv";
00094 std::string Logging::transport_frames_file = "transport_frames.csv";
00095
00096
00097
00098
00099
00100
00101
00102
00103
00104
00105
00106
00107
00108
00109
00110
00111
00112
00113
00114
00115
00116
00117
00118
00119
00120
00121
00122
00123
00124
00125
00126
00127
00128
00129
00130
00131
00132
00133
00134
00135
00136
00137
00138
00139
00140
00141
00142
00143
00144
00145
00146
00147
00148
00149
00150
00151
00152
00153
00154
00155
00156
00157
00158
00159
00160
00161
00162
00163
00164
00165
00166
00167 boost::mutex Logging::mtx_logging;
00168
00169
00170
00171 #endif