added a new namespace for update functions
This commit is contained in:
parent
58c09093a7
commit
e953de6191
|
@ -3,161 +3,169 @@
|
|||
|
||||
#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)
|
||||
|
||||
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 {
|
||||
CODE_RUNNING = 0, // Code executing
|
||||
CODE_STANDBY, // Standing by for others to update
|
||||
} code_states_e;
|
||||
|
||||
/*********************/
|
||||
/*Message types */
|
||||
/********************/
|
||||
|
||||
typedef enum {
|
||||
SENT_CODE = 0, // Broadcast code
|
||||
RESEND_CODE, // ReBroadcast request
|
||||
} code_message_e;
|
||||
|
||||
/*************************/
|
||||
/*Updater message queue */
|
||||
/*************************/
|
||||
|
||||
struct updater_msgqueue_s
|
||||
namespace buzz_update
|
||||
{
|
||||
uint8_t* queue;
|
||||
uint8_t* size;
|
||||
};
|
||||
typedef struct updater_msgqueue_s* updater_msgqueue_t;
|
||||
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 */
|
||||
/********************/
|
||||
|
||||
struct updater_code_s
|
||||
{
|
||||
uint8_t* bcode;
|
||||
uint8_t* bcode_size;
|
||||
};
|
||||
typedef struct updater_code_s* updater_code_t;
|
||||
typedef enum {
|
||||
CODE_RUNNING = 0, // Code executing
|
||||
CODE_STANDBY, // Standing by for others to update
|
||||
} code_states_e;
|
||||
|
||||
/**************************/
|
||||
/*Updater data*/
|
||||
/**************************/
|
||||
/*********************/
|
||||
/*Message types */
|
||||
/********************/
|
||||
|
||||
struct buzz_updater_elem_s
|
||||
{
|
||||
/* robot id */
|
||||
// uint16_t robotid;
|
||||
/*current Bytecode content */
|
||||
uint8_t* bcode;
|
||||
/*old Bytecode name */
|
||||
const char* old_bcode;
|
||||
/*current bcode size*/
|
||||
size_t* bcode_size;
|
||||
/*Update patch*/
|
||||
uint8_t* patch;
|
||||
/* Update patch size*/
|
||||
size_t* patch_size;
|
||||
/*current Bytecode content */
|
||||
uint8_t* standby_bcode;
|
||||
/*current bcode size*/
|
||||
size_t* standby_bcode_size;
|
||||
/*updater out msg queue */
|
||||
updater_msgqueue_t outmsg_queue;
|
||||
/*updater in msg queue*/
|
||||
updater_msgqueue_t inmsg_queue;
|
||||
/*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 enum {
|
||||
SENT_CODE = 0, // Broadcast code
|
||||
RESEND_CODE, // ReBroadcast request
|
||||
} code_message_e;
|
||||
|
||||
/**************************************************************************/
|
||||
/*Updater routine from msg processing to file checks to be called from main*/
|
||||
/**************************************************************************/
|
||||
void update_routine();
|
||||
/*************************/
|
||||
/*Updater message queue */
|
||||
/*************************/
|
||||
|
||||
/************************************************/
|
||||
/*Initalizes the updater */
|
||||
/************************************************/
|
||||
void init_update_monitor(const char* bo_filename, const char* stand_by_script, const char* dbgfname, int robot_id);
|
||||
struct updater_msgqueue_s
|
||||
{
|
||||
uint8_t* queue;
|
||||
uint8_t* size;
|
||||
};
|
||||
typedef struct updater_msgqueue_s* updater_msgqueue_t;
|
||||
|
||||
/*********************************************************/
|
||||
/*Appends buffer of given size to in msg queue of updater*/
|
||||
/*********************************************************/
|
||||
struct updater_code_s
|
||||
{
|
||||
uint8_t* bcode;
|
||||
uint8_t* bcode_size;
|
||||
};
|
||||
typedef struct updater_code_s* updater_code_t;
|
||||
|
||||
void code_message_inqueue_append(uint8_t* msg, uint16_t size);
|
||||
/**************************/
|
||||
/*Updater data*/
|
||||
/**************************/
|
||||
|
||||
/*********************************************************/
|
||||
/*Processes messages inside the queue of the updater*/
|
||||
/*********************************************************/
|
||||
struct buzz_updater_elem_s
|
||||
{
|
||||
/* robot id */
|
||||
// uint16_t robotid;
|
||||
/*current Bytecode content */
|
||||
uint8_t* bcode;
|
||||
/*old Bytecode name */
|
||||
const char* old_bcode;
|
||||
/*current bcode size*/
|
||||
size_t* bcode_size;
|
||||
/*Update patch*/
|
||||
uint8_t* patch;
|
||||
/* Update patch size*/
|
||||
size_t* patch_size;
|
||||
/*current Bytecode content */
|
||||
uint8_t* standby_bcode;
|
||||
/*current bcode size*/
|
||||
size_t* standby_bcode_size;
|
||||
/*updater out msg queue */
|
||||
updater_msgqueue_t outmsg_queue;
|
||||
/*updater in msg queue*/
|
||||
updater_msgqueue_t inmsg_queue;
|
||||
/*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;
|
||||
|
||||
void code_message_inqueue_process();
|
||||
/**************************************************************************/
|
||||
/*Updater routine from msg processing to file checks to be called from main*/
|
||||
/**************************************************************************/
|
||||
void update_routine();
|
||||
|
||||
/*****************************************************/
|
||||
/*Obtains messages from out msgs queue of the updater*/
|
||||
/*******************************************************/
|
||||
uint8_t* getupdater_out_msg();
|
||||
/************************************************/
|
||||
/*Initalizes the updater */
|
||||
/************************************************/
|
||||
void init_update_monitor(const char* bo_filename, const char* stand_by_script, const char* dbgfname, int robot_id);
|
||||
|
||||
/******************************************************/
|
||||
/*Obtains out msg queue size*/
|
||||
/*****************************************************/
|
||||
uint8_t* getupdate_out_msg_size();
|
||||
/*********************************************************/
|
||||
/*Appends buffer of given size to in msg queue of updater*/
|
||||
/*********************************************************/
|
||||
|
||||
/**************************************************/
|
||||
/*Destroys the out msg queue*/
|
||||
/*************************************************/
|
||||
void destroy_out_msg_queue();
|
||||
void code_message_inqueue_append(uint8_t* msg, uint16_t size);
|
||||
|
||||
// buzz_updater_elem_t get_updater();
|
||||
/***************************************************/
|
||||
/*Sets bzz file name*/
|
||||
/***************************************************/
|
||||
void set_bzz_file(const char* in_bzz_file);
|
||||
/*********************************************************/
|
||||
/*Processes messages inside the queue of the updater*/
|
||||
/*********************************************************/
|
||||
|
||||
/****************************************************/
|
||||
/*Tests the code from a buffer*/
|
||||
/***************************************************/
|
||||
void code_message_inqueue_process();
|
||||
|
||||
int test_set_code(uint8_t* BO_BUF, const char* dbgfname, size_t bcode_size);
|
||||
/*****************************************************/
|
||||
/*Obtains messages from out msgs queue of the updater*/
|
||||
/*******************************************************/
|
||||
uint8_t* getupdater_out_msg();
|
||||
|
||||
/****************************************************/
|
||||
/*Destroys the updater*/
|
||||
/***************************************************/
|
||||
/******************************************************/
|
||||
/*Obtains out msg queue size*/
|
||||
/*****************************************************/
|
||||
uint8_t* getupdate_out_msg_size();
|
||||
|
||||
void destroy_updater();
|
||||
/**************************************************/
|
||||
/*Destroys the out msg queue*/
|
||||
/*************************************************/
|
||||
void destroy_out_msg_queue();
|
||||
|
||||
/****************************************************/
|
||||
/*Checks for updater message*/
|
||||
/***************************************************/
|
||||
// buzz_updater_elem_t get_updater();
|
||||
/***************************************************/
|
||||
/*Sets bzz file name*/
|
||||
/***************************************************/
|
||||
void set_bzz_file(const char* in_bzz_file);
|
||||
|
||||
int is_msg_present();
|
||||
/****************************************************/
|
||||
/*Tests the code from a buffer*/
|
||||
/***************************************************/
|
||||
|
||||
/****************************************************/
|
||||
/*Compiles a bzz script to bo and bdbg*/
|
||||
/***************************************************/
|
||||
int test_set_code(uint8_t* BO_BUF, const char* dbgfname, size_t bcode_size);
|
||||
|
||||
int compile_bzz(std::string bzz_file);
|
||||
/****************************************************/
|
||||
/*Destroys the updater*/
|
||||
/***************************************************/
|
||||
|
||||
/****************************************************/
|
||||
/*Set number of robots in the updater*/
|
||||
/***************************************************/
|
||||
void destroy_updater();
|
||||
|
||||
void updates_set_robots(int robots);
|
||||
/****************************************************/
|
||||
/*Checks for updater message*/
|
||||
/***************************************************/
|
||||
|
||||
int is_msg_present();
|
||||
|
||||
/****************************************************/
|
||||
/*Compiles a bzz script to bo and bdbg*/
|
||||
/***************************************************/
|
||||
|
||||
int compile_bzz(std::string bzz_file);
|
||||
|
||||
/****************************************************/
|
||||
/*Set number of robots in the updater*/
|
||||
/***************************************************/
|
||||
|
||||
void updates_set_robots(int robots);
|
||||
}
|
||||
#endif
|
||||
|
|
1264
src/buzz_update.cpp
1264
src/buzz_update.cpp
File diff suppressed because it is too large
Load Diff
|
@ -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);
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue