logger
This commit is contained in:
parent
904bdc199b
commit
745cc75c56
|
@ -6,7 +6,7 @@
|
|||
#include <buzz/buzzdict.h>
|
||||
#include <buzz/buzzdarray.h>
|
||||
#include <buzz/buzzvstig.h>
|
||||
|
||||
#include <fstream>
|
||||
#define delete_p(p) do { free(p); p = NULL; } while(0)
|
||||
|
||||
|
||||
|
@ -133,4 +133,5 @@ int compile_bzz();
|
|||
|
||||
void updates_set_robots(int robots);
|
||||
|
||||
void collect_data(std::ofstream &logger);
|
||||
#endif
|
||||
|
|
|
@ -121,6 +121,8 @@ private:
|
|||
int setpoint_counter;
|
||||
double my_x = 0, my_y = 0;
|
||||
|
||||
std::ofstream log;
|
||||
|
||||
/*Commands for flight controller*/
|
||||
//mavros_msgs::CommandInt cmd_srv;
|
||||
mavros_msgs::CommandLong cmd_srv;
|
||||
|
|
|
@ -15,7 +15,7 @@
|
|||
static struct timeval t1, t2;
|
||||
static int timer_steps=0;
|
||||
//static clock_t end;
|
||||
void collect_data();
|
||||
|
||||
/*Temp end */
|
||||
static int fd,wd =0;
|
||||
static int old_update =0;
|
||||
|
@ -89,6 +89,7 @@ void init_update_monitor(const char* bo_filename, const char* stand_by_script){
|
|||
//neigh = 0;
|
||||
//updater->outmsg_queue=
|
||||
// update_table->barrier=nvs;
|
||||
// open logger
|
||||
|
||||
}
|
||||
/*Check for .bzz file chages*/
|
||||
|
@ -178,6 +179,7 @@ void code_message_inqueue_process(){
|
|||
(char*) dbgf_name,(size_t)update_bcode_size) ) {
|
||||
*(uint16_t*)(updater->update_no)=update_no;
|
||||
neigh=1;
|
||||
gettimeofday(&t1, NULL);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -241,11 +243,11 @@ void update_routine(const char* bcfname,
|
|||
}
|
||||
|
||||
else{
|
||||
//gettimeofday(&t1, NULL);
|
||||
|
||||
if(neigh==0 && (!is_msg_present())){
|
||||
ROS_INFO("Sending code... \n");
|
||||
code_message_outqueue_append();
|
||||
|
||||
gettimeofday(&t1, NULL);
|
||||
}
|
||||
timer_steps++;
|
||||
buzzvm_pushs(VM, buzzvm_string_register(VM, "barrier_val",1));
|
||||
|
@ -385,7 +387,7 @@ void destroy_updater(){
|
|||
//
|
||||
inotify_rm_watch(fd,wd);
|
||||
close(fd);
|
||||
}
|
||||
}
|
||||
|
||||
void set_bzz_file(const char* in_bzz_file){
|
||||
bzz_file=in_bzz_file;
|
||||
|
@ -412,12 +414,13 @@ int compile_bzz(){
|
|||
ROS_WARN("Launching buzz compilation for update: %s", bzzfile_in_compile.str().c_str());
|
||||
return system(bzzfile_in_compile.str().c_str());
|
||||
}
|
||||
void collect_data(){
|
||||
void collect_data(std::ofstream &logger){
|
||||
//fprintf(stdout,"start and end time in data collection Info : %f,%f",(double)begin,(double)end);
|
||||
double time_spent = (t2.tv_sec - t1.tv_sec) * 1000.0; //(double)(end - begin) / CLOCKS_PER_SEC;
|
||||
time_spent += (t2.tv_usec - t1.tv_usec) / 1000.0;
|
||||
//int bytecodesize=(int);
|
||||
fprintf(stdout,"Data logger Info : %i , %i , %f , %ld , %i , %d \n",(int)no_of_robot,neigh,time_spent,*(size_t*)updater->bcode_size,(int)no_of_robot,*(uint8_t*)updater->update_no);
|
||||
logger<<(int)no_of_robot<<","<<neigh<<","<<(double)time_spent<<","<<(int)timer_steps<<","<<*(size_t*)updater->bcode_size<<","<<(int)no_of_robot<<","<<*(uint8_t*)updater->update_no;
|
||||
//fprintf(stdout,"Data logger Info : %i , %i , %f , %ld , %i , %d \n",(int)no_of_robot,neigh,time_spent,*(size_t*)updater->bcode_size,(int)no_of_robot,*(uint8_t*)updater->update_no);
|
||||
//FILE *Fileptr;
|
||||
//Fileptr=fopen("/home/ubuntu/ROS_WS/update_logger.csv", "a");
|
||||
//fprintf(Fileptr,"%i,%i,%i,%i,%i,%u\n",(int)buzz_utility::get_robotid(),neigh,timer_steps,(int)*(size_t*)updater->bcode_size,(int)no_of_robot, *(uint8_t*)updater->update_no);
|
||||
|
|
|
@ -45,6 +45,9 @@ namespace rosbzz_node{
|
|||
} else {
|
||||
robot_id= strtol(robot_name.c_str() + 5, NULL, 10);
|
||||
}
|
||||
std::string path = bzzfile_name.substr(0, bzzfile_name.find_last_of("\\/")) + "/";
|
||||
path+="Update.log";
|
||||
log.open(path.c_str(), std::ios_base::trunc | std::ios_base::out);
|
||||
}
|
||||
|
||||
/*---------------------
|
||||
|
@ -57,6 +60,7 @@ namespace rosbzz_node{
|
|||
buzz_utility::buzz_script_destroy();
|
||||
/* Stop the robot */
|
||||
uav_done();
|
||||
log.close();
|
||||
}
|
||||
|
||||
void roscontroller::GetRobotId()
|
||||
|
@ -106,6 +110,9 @@ namespace rosbzz_node{
|
|||
if(get_update_status()){
|
||||
set_read_update_status();
|
||||
multi_msg=true;
|
||||
log<<cur_pos.latitude<<","<<cur_pos.longitude<<","<<cur_pos.altitude<<",";
|
||||
collect_data(log);
|
||||
log<<std::endl;
|
||||
}
|
||||
/*Set ROBOTS variable for barrier in .bzz from neighbours count*/
|
||||
//no_of_robots=get_number_of_robots();
|
||||
|
|
Loading…
Reference in New Issue