added a new namespace for update functions

This commit is contained in:
vivek-shankar 2018-06-06 22:55:49 -04:00
parent 58c09093a7
commit e953de6191
3 changed files with 772 additions and 762 deletions

View File

@ -3,64 +3,72 @@
#include <stdlib.h>
#include <stdio.h>
#include <fcntl.h>
#include <unistd.h>
#include <string.h>
#include <sys/time.h>
#include <sys/inotify.h>
#include <buzz/buzztype.h>
#include <buzz/buzzdict.h>
#include <buzz/buzzdarray.h>
#include <buzz/buzzvstig.h>
#include <buzz_utility.h>
#include <fstream>
#define delete_p(p) \
do \
{ \
free(p); \
p = NULL; \
} while (0)
namespace buzz_update
{
static const uint16_t CODE_REQUEST_PADDING = 250;
static const uint16_t MIN_UPDATE_PACKET = 251;
static const uint16_t UPDATE_CODE_HEADER_SIZE = 5;
static const uint16_t TIMEOUT_FOR_ROLLBACK = 50;
/*********************/
/* Updater states */
/********************/
static const uint16_t CODE_REQUEST_PADDING = 250;
static const uint16_t MIN_UPDATE_PACKET = 251;
static const uint16_t UPDATE_CODE_HEADER_SIZE = 5;
static const uint16_t TIMEOUT_FOR_ROLLBACK = 50;
/*********************/
/* Updater states */
/********************/
typedef enum {
typedef enum {
CODE_RUNNING = 0, // Code executing
CODE_STANDBY, // Standing by for others to update
} code_states_e;
} code_states_e;
/*********************/
/*Message types */
/********************/
/*********************/
/*Message types */
/********************/
typedef enum {
typedef enum {
SENT_CODE = 0, // Broadcast code
RESEND_CODE, // ReBroadcast request
} code_message_e;
} code_message_e;
/*************************/
/*Updater message queue */
/*************************/
/*************************/
/*Updater message queue */
/*************************/
struct updater_msgqueue_s
{
struct updater_msgqueue_s
{
uint8_t* queue;
uint8_t* size;
};
typedef struct updater_msgqueue_s* updater_msgqueue_t;
};
typedef struct updater_msgqueue_s* updater_msgqueue_t;
struct updater_code_s
{
struct updater_code_s
{
uint8_t* bcode;
uint8_t* bcode_size;
};
typedef struct updater_code_s* updater_code_t;
};
typedef struct updater_code_s* updater_code_t;
/**************************/
/*Updater data*/
/**************************/
/**************************/
/*Updater data*/
/**************************/
struct buzz_updater_elem_s
{
struct buzz_updater_elem_s
{
/* robot id */
// uint16_t robotid;
/*current Bytecode content */
@ -84,80 +92,80 @@ struct buzz_updater_elem_s
/*Current state of the updater one in code_states_e ENUM*/
int* mode;
uint8_t* update_no;
};
typedef struct buzz_updater_elem_s* buzz_updater_elem_t;
};
typedef struct buzz_updater_elem_s* buzz_updater_elem_t;
/**************************************************************************/
/*Updater routine from msg processing to file checks to be called from main*/
/**************************************************************************/
void update_routine();
/**************************************************************************/
/*Updater routine from msg processing to file checks to be called from main*/
/**************************************************************************/
void update_routine();
/************************************************/
/*Initalizes the updater */
/************************************************/
void init_update_monitor(const char* bo_filename, const char* stand_by_script, const char* dbgfname, int robot_id);
/************************************************/
/*Initalizes the updater */
/************************************************/
void init_update_monitor(const char* bo_filename, const char* stand_by_script, const char* dbgfname, int robot_id);
/*********************************************************/
/*Appends buffer of given size to in msg queue of updater*/
/*********************************************************/
/*********************************************************/
/*Appends buffer of given size to in msg queue of updater*/
/*********************************************************/
void code_message_inqueue_append(uint8_t* msg, uint16_t size);
void code_message_inqueue_append(uint8_t* msg, uint16_t size);
/*********************************************************/
/*Processes messages inside the queue of the updater*/
/*********************************************************/
/*********************************************************/
/*Processes messages inside the queue of the updater*/
/*********************************************************/
void code_message_inqueue_process();
void code_message_inqueue_process();
/*****************************************************/
/*Obtains messages from out msgs queue of the updater*/
/*******************************************************/
uint8_t* getupdater_out_msg();
/*****************************************************/
/*Obtains messages from out msgs queue of the updater*/
/*******************************************************/
uint8_t* getupdater_out_msg();
/******************************************************/
/*Obtains out msg queue size*/
/*****************************************************/
uint8_t* getupdate_out_msg_size();
/******************************************************/
/*Obtains out msg queue size*/
/*****************************************************/
uint8_t* getupdate_out_msg_size();
/**************************************************/
/*Destroys the out msg queue*/
/*************************************************/
void destroy_out_msg_queue();
/**************************************************/
/*Destroys the out msg queue*/
/*************************************************/
void destroy_out_msg_queue();
// buzz_updater_elem_t get_updater();
/***************************************************/
/*Sets bzz file name*/
/***************************************************/
void set_bzz_file(const char* in_bzz_file);
// buzz_updater_elem_t get_updater();
/***************************************************/
/*Sets bzz file name*/
/***************************************************/
void set_bzz_file(const char* in_bzz_file);
/****************************************************/
/*Tests the code from a buffer*/
/***************************************************/
/****************************************************/
/*Tests the code from a buffer*/
/***************************************************/
int test_set_code(uint8_t* BO_BUF, const char* dbgfname, size_t bcode_size);
int test_set_code(uint8_t* BO_BUF, const char* dbgfname, size_t bcode_size);
/****************************************************/
/*Destroys the updater*/
/***************************************************/
/****************************************************/
/*Destroys the updater*/
/***************************************************/
void destroy_updater();
void destroy_updater();
/****************************************************/
/*Checks for updater message*/
/***************************************************/
/****************************************************/
/*Checks for updater message*/
/***************************************************/
int is_msg_present();
int is_msg_present();
/****************************************************/
/*Compiles a bzz script to bo and bdbg*/
/***************************************************/
/****************************************************/
/*Compiles a bzz script to bo and bdbg*/
/***************************************************/
int compile_bzz(std::string bzz_file);
int compile_bzz(std::string bzz_file);
/****************************************************/
/*Set number of robots in the updater*/
/***************************************************/
void updates_set_robots(int robots);
/****************************************************/
/*Set number of robots in the updater*/
/***************************************************/
void updates_set_robots(int robots);
}
#endif

View File

@ -1,41 +1,42 @@
#include <stdio.h>
#include <stdlib.h>
#include <fcntl.h>
#include <unistd.h>
#include <sys/inotify.h>
/** @file buzz_utility.cpp
* @version 1.0
* @date 27.09.2016
* @brief Buzz Implementation as a node in ROS.
* @author Vivek Shankar Varadharajan and David St-Onge
* @copyright 2016 MistLab. All rights reserved.
*/
#include "buzz_update.h"
#include <buzz_utility.h>
#include <string.h>
#include <buzz/buzzdebug.h>
#include <sys/time.h>
/*Temp for data collection*/
// static int neigh=-1;
static struct timeval t1, t2;
static int timer_steps = 0;
// static clock_t end;
namespace buzz_update{
/*Temp for data collection*/
// static int neigh=-1;
static struct timeval t1, t2;
static int timer_steps = 0;
// static clock_t end;
/*Temp end */
static int fd, wd = 0;
static int old_update = 0;
static buzz_updater_elem_t updater;
static int no_of_robot;
static const char* dbgf_name;
static const char* bcfname;
static const char* old_bcfname = "old_bcode.bo";
static const char* bzz_file;
static int Robot_id = 0;
static int neigh = -1;
static int updater_msg_ready;
static uint16_t update_try_counter = 0;
static int updated = 0;
static const uint16_t MAX_UPDATE_TRY = 5;
static int packet_id_ = 0;
static size_t old_byte_code_size = 0;
/*Temp end */
static int fd, wd = 0;
static int old_update = 0;
static buzz_updater_elem_t updater;
static int no_of_robot;
static const char* dbgf_name;
static const char* bcfname;
static const char* old_bcfname = "old_bcode.bo";
static const char* bzz_file;
static int Robot_id = 0;
static int neigh = -1;
static int updater_msg_ready;
static uint16_t update_try_counter = 0;
static int updated = 0;
static const uint16_t MAX_UPDATE_TRY = 5;
static int packet_id_ = 0;
static size_t old_byte_code_size = 0;
/*Initialize updater*/
void init_update_monitor(const char* bo_filename, const char* stand_by_script, const char* dbgfname, int robot_id)
{
/*Initialize updater*/
void init_update_monitor(const char* bo_filename, const char* stand_by_script, const char* dbgfname, int robot_id)
{
buzzvm_t VM = buzz_utility::get_vm();
Robot_id = robot_id;
dbgf_name = dbgfname;
bcfname = bo_filename;
@ -117,10 +118,10 @@ void init_update_monitor(const char* bo_filename, const char* stand_by_script, c
fp = fopen("old_bcode.bo", "wb");
fwrite((updater->bcode), *(size_t*)updater->bcode_size, 1, fp);
fclose(fp);
}
/*Check for .bzz file chages*/
int check_update()
{
}
/*Check for .bzz file chages*/
int check_update()
{
char buf[1024];
int check = 0;
int i = 0;
@ -150,10 +151,10 @@ int check_update()
if (!check)
old_update = 0;
return check;
}
}
int test_patch(std::string& path, std::string& name1, size_t update_patch_size, uint8_t* patch)
{
int test_patch(std::string& path, std::string& name1, size_t update_patch_size, uint8_t* patch)
{
if (SIMULATION == 1)
{
return 1;
@ -176,10 +177,10 @@ int test_patch(std::string& path, std::string& name1, size_t update_patch_size,
else
return 1;
}
}
}
updater_code_t obtain_patched_bo(std::string& path, std::string& name1)
{
updater_code_t obtain_patched_bo(std::string& path, std::string& name1)
{
if (SIMULATION == 1)
{
/*Read the exsisting file to simulate the patching*/
@ -244,10 +245,10 @@ updater_code_t obtain_patched_bo(std::string& path, std::string& name1)
return update_code;
}
}
}
void code_message_outqueue_append()
{
void code_message_outqueue_append()
{
updater->outmsg_queue = (updater_msgqueue_t)malloc(sizeof(struct updater_msgqueue_s));
/* if size less than 250 Pad with zeors to assure transmission*/
uint16_t size = UPDATE_CODE_HEADER_SIZE + *(size_t*)(updater->patch_size);
@ -269,10 +270,10 @@ void code_message_outqueue_append()
memcpy(updater->outmsg_queue->queue + size, updater->patch, *(size_t*)(updater->patch_size));
// size += (uint16_t) * (size_t*)(updater->patch_size);
updater_msg_ready = 1;
}
}
void outqueue_append_code_request(uint16_t update_no)
{
void outqueue_append_code_request(uint16_t update_no)
{
updater->outmsg_queue = (updater_msgqueue_t)malloc(sizeof(struct updater_msgqueue_s));
uint16_t size = 0;
updater->outmsg_queue->queue = (uint8_t*)malloc(2 * sizeof(uint16_t) + sizeof(uint8_t) + CODE_REQUEST_PADDING);
@ -289,24 +290,24 @@ void outqueue_append_code_request(uint16_t update_no)
*(uint16_t*)(updater->outmsg_queue->size) = size + CODE_REQUEST_PADDING;
updater_msg_ready = 1;
ROS_INFO("[Debug] Requested update no. %u with try: %u \n", update_no, update_try_counter);
}
}
void code_message_inqueue_append(uint8_t* msg, uint16_t size)
{
void code_message_inqueue_append(uint8_t* msg, uint16_t size)
{
updater->inmsg_queue = (updater_msgqueue_t)malloc(sizeof(struct updater_msgqueue_s));
// ROS_INFO("[DEBUG] Updater append code of size %d\n", (int) size);
updater->inmsg_queue->queue = (uint8_t*)malloc(size);
updater->inmsg_queue->size = (uint8_t*)malloc(sizeof(uint16_t));
memcpy(updater->inmsg_queue->queue, msg, size);
*(uint16_t*)(updater->inmsg_queue->size) = size;
}
/*Used for data logging*/
/*void set_packet_id(int packet_id)
{
}
/*Used for data logging*/
/*void set_packet_id(int packet_id)
{
packet_id_ = packet_id;
}*/
void code_message_inqueue_process()
{
}*/
void code_message_inqueue_process()
{
int size = 0;
updater_code_t out_code = NULL;
@ -394,10 +395,10 @@ void code_message_inqueue_process()
delete_p(updater->inmsg_queue->queue);
delete_p(updater->inmsg_queue->size);
delete_p(updater->inmsg_queue);
}
}
void create_update_patch()
{
void create_update_patch()
{
std::stringstream genpatch;
std::string bzzfile_name(bzz_file);
@ -447,10 +448,10 @@ void create_update_patch()
/* Delete the diff file */
remove(patchfileName.str().c_str());
}
}
void update_routine()
{
void update_routine()
{
buzzvm_t VM = buzz_utility::get_vm();
buzzvm_pushs(VM, buzzvm_string_register(VM, "update_no", 1));
buzzvm_pushi(VM, *(uint16_t*)(updater->update_no));
@ -539,21 +540,21 @@ void update_routine()
timer_steps = 0;
}
}
}
}
uint8_t* getupdater_out_msg()
{
uint8_t* getupdater_out_msg()
{
return (uint8_t*)updater->outmsg_queue->queue;
}
}
uint8_t* getupdate_out_msg_size()
{
uint8_t* getupdate_out_msg_size()
{
// fprintf(stdout,"[Debug from get out size in util: ]size = %i \n",*(uint16_t*)updater->outmsg_queue->size);
return (uint8_t*)updater->outmsg_queue->size;
}
}
int test_set_code(uint8_t* BO_BUF, const char* dbgfname, size_t bcode_size)
{
int test_set_code(uint8_t* BO_BUF, const char* dbgfname, size_t bcode_size)
{
if (buzz_utility::buzz_update_init_test(BO_BUF, dbgfname, bcode_size))
{
ROS_WARN("Initializtion of script test passed\n");
@ -623,27 +624,27 @@ int test_set_code(uint8_t* BO_BUF, const char* dbgfname, size_t bcode_size)
}
return 0;
}
}
}
void destroy_out_msg_queue()
{
void destroy_out_msg_queue()
{
// fprintf(stdout,"out queue freed\n");
delete_p(updater->outmsg_queue->queue);
delete_p(updater->outmsg_queue->size);
delete_p(updater->outmsg_queue);
updater_msg_ready = 0;
}
}
int is_msg_present()
{
int is_msg_present()
{
return updater_msg_ready;
}
/*buzz_updater_elem_t get_updater()
{
}
/*buzz_updater_elem_t get_updater()
{
return updater;
}*/
void destroy_updater()
{
}*/
void destroy_updater()
{
delete_p(updater->bcode);
delete_p(updater->bcode_size);
delete_p(updater->standby_bcode);
@ -664,23 +665,23 @@ void destroy_updater()
}
inotify_rm_watch(fd, wd);
close(fd);
}
}
void set_bzz_file(const char* in_bzz_file)
{
void set_bzz_file(const char* in_bzz_file)
{
bzz_file = in_bzz_file;
}
}
void updates_set_robots(int robots)
{
void updates_set_robots(int robots)
{
no_of_robot = robots;
}
}
/*--------------------------------------------------------
/ Create Buzz bytecode from the bzz script inputed
/-------------------------------------------------------*/
int compile_bzz(std::string bzz_file)
{
/*--------------------------------------------------------
/ Create Buzz bytecode from the bzz script inputed
/-------------------------------------------------------*/
int compile_bzz(std::string bzz_file)
{
/*Compile the buzz code .bzz to .bo*/
std::string bzzfile_name(bzz_file);
stringstream bzzfile_in_compile;
@ -693,16 +694,17 @@ int compile_bzz(std::string bzz_file)
bzzfile_in_compile << bzzfile_name;
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(std::ofstream& logger)
{
/*void collect_data(std::ofstream& logger)
{
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;
// RID,update trigger,time steps taken,old byte code size, new bytecode size, patch size,update number,
//
Patch_packets_received_counter,Patch_request_packets_received,Patch_packets_sent_counter,Patch_request_packets_sent_counter
Patch_packets_received_counter,Patch_request_packets_received,Patch_packets_sent_counter,Patch_request_packets_sent_counter
logger << (int)no_of_robot << "," << neigh << "," << (double)time_spent << "," << (int)timer_steps << ","
<< old_byte_code_size << "," << *(size_t*)updater->bcode_size << "," << *(size_t*)updater->patch_size << ","
<< (int)*(uint8_t*)updater->update_no << "," << (int)packet_id_;
}*/
}*/
}

View File

@ -26,7 +26,7 @@ roscontroller::roscontroller(ros::NodeHandle& n_c, ros::NodeHandle& n_c_priv)
std::string fname = Compile_bzz(bzzfile_name);
bcfname = fname + ".bo";
dbgfname = fname + ".bdb";
set_bzz_file(bzzfile_name.c_str());
buzz_update::set_bzz_file(bzzfile_name.c_str());
buzzuav_closures::setWPlist(bzzfile_name.substr(0, bzzfile_name.find_last_of("\\/")) + "/");
// Initialize variables
SetMode("LOITER", 0);
@ -106,7 +106,7 @@ void roscontroller::RosControllerRun()
ROS_INFO("[%i] Bytecode file found and set", robot_id);
std::string standby_bo = Compile_bzz(stand_by) + ".bo";
// Intialize the update monitor
init_update_monitor(bcfname.c_str(), standby_bo.c_str(), dbgfname.c_str(), robot_id);
buzz_update::init_update_monitor(bcfname.c_str(), standby_bo.c_str(), dbgfname.c_str(), robot_id);
// set ROS loop rate
ros::Rate loop_rate(BUZZRATE);
// DEBUG
@ -119,7 +119,7 @@ void roscontroller::RosControllerRun()
grid_publisher();
send_MPpayload();
// Check updater state and step code
update_routine();
buzz_update::update_routine();
ROS_WARN("OUT OF UPDATE ROUTINE");
if (time_step == BUZZRATE)
{
@ -152,7 +152,7 @@ void roscontroller::RosControllerRun()
// Set ROBOTS variable (swarm size)
get_number_of_robots();
buzz_utility::set_robot_var(no_of_robots);
updates_set_robots(no_of_robots);
buzz_update::updates_set_robots(no_of_robots);
// get_xbee_status(); // commented out because it may slow down the node too much, to be tested
ros::spinOnce();
@ -570,10 +570,10 @@ with size......... | /
delete[] out;
delete[] payload_out_ptr;
// Check for updater message if present send
if (is_msg_present())
if (buzz_update::is_msg_present())
{
uint8_t* buff_send = 0;
uint16_t updater_msgSize = *(uint16_t*)(getupdate_out_msg_size());
uint16_t updater_msgSize = *(uint16_t*)(buzz_update::getupdate_out_msg_size());
;
int tot = 0;
mavros_msgs::Mavlink update_packets;
@ -586,10 +586,10 @@ with size......... | /
*(uint16_t*)(buff_send + tot) = updater_msgSize;
tot += sizeof(uint16_t);
// Append updater msgs
memcpy(buff_send + tot, (uint8_t*)(getupdater_out_msg()), updater_msgSize);
memcpy(buff_send + tot, (uint8_t*)(buzz_update::getupdater_out_msg()), updater_msgSize);
tot += updater_msgSize;
// Destroy the updater out msg queue
destroy_out_msg_queue();
buzz_update::destroy_out_msg_queue();
uint16_t total_size = (ceil((float)(float)tot / (float)sizeof(uint64_t)));
uint64_t* payload_64 = new uint64_t[total_size];
memcpy((void*)payload_64, (void*)buff_send, total_size * sizeof(uint64_t));
@ -1012,8 +1012,8 @@ void roscontroller::payload_obt(const mavros_msgs::Mavlink::ConstPtr& msg)
fprintf(stdout, "Update packet received, read msg size : %u \n", unMsgSize);
if (unMsgSize > 0)
{
code_message_inqueue_append((uint8_t*)(pl + sizeof(uint16_t)), unMsgSize);
code_message_inqueue_process();
buzz_update::code_message_inqueue_append((uint8_t*)(pl + sizeof(uint16_t)), unMsgSize);
buzz_update::code_message_inqueue_process();
}
free(pl);
}