for testing #2 - waypoints included
This commit is contained in:
parent
f01804b5a3
commit
24defade59
@ -160,7 +160,7 @@ private:
|
|||||||
|
|
||||||
void Subscribe(ros::NodeHandle n_c);
|
void Subscribe(ros::NodeHandle n_c);
|
||||||
|
|
||||||
void WaypointMissionSetup();
|
void WaypointMissionSetup(float lat, float lng, float alg);
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -8,72 +8,69 @@
|
|||||||
|
|
||||||
#include <buzz_utility.h>
|
#include <buzz_utility.h>
|
||||||
|
|
||||||
namespace buzz_utility{
|
namespace buzz_utility {
|
||||||
|
|
||||||
/****************************************/
|
/****************************************/
|
||||||
/****************************************/
|
/****************************************/
|
||||||
|
|
||||||
static buzzvm_t VM = 0;
|
static buzzvm_t VM = 0;
|
||||||
static char* BO_FNAME = 0;
|
static char* BO_FNAME = 0;
|
||||||
static uint8_t* BO_BUF = 0;
|
static uint8_t* BO_BUF = 0;
|
||||||
static buzzdebug_t DBG_INFO = 0;
|
static buzzdebug_t DBG_INFO = 0;
|
||||||
static uint8_t MSG_SIZE = 50; // Only 100 bytes of Buzz messages every step
|
static uint8_t MSG_SIZE = 50; // Only 100 bytes of Buzz messages every step
|
||||||
static int MAX_MSG_SIZE = 10000; // Maximum Msg size for sending update packets
|
static int MAX_MSG_SIZE = 10000; // Maximum Msg size for sending update packets
|
||||||
|
|
||||||
|
|
||||||
/****************************************/
|
/****************************************/
|
||||||
/*adds neighbours position*/
|
/*adds neighbours position*/
|
||||||
void neighbour_pos_callback(std::map< int, Pos_struct> neighbours_pos_map){
|
void neighbour_pos_callback(std::map<int, Pos_struct> neighbours_pos_map) {
|
||||||
/* Reset neighbor information */
|
/* Reset neighbor information */
|
||||||
buzzneighbors_reset(VM);
|
buzzneighbors_reset(VM);
|
||||||
/* Get robot id and update neighbor information */
|
/* Get robot id and update neighbor information */
|
||||||
map< int, Pos_struct >::iterator it;
|
map<int, Pos_struct>::iterator it;
|
||||||
for (it=neighbours_pos_map.begin(); it!=neighbours_pos_map.end(); ++it){
|
for (it = neighbours_pos_map.begin(); it != neighbours_pos_map.end(); ++it) {
|
||||||
buzzneighbors_add(VM,
|
buzzneighbors_add(VM, it->first, (it->second).x, (it->second).y,
|
||||||
it->first,
|
|
||||||
(it->second).x,
|
|
||||||
(it->second).y,
|
|
||||||
(it->second).z);
|
(it->second).z);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
/**************************************************************************/
|
/**************************************************************************/
|
||||||
/*Deserializes uint64_t into 4 uint16_t, freeing out is left to the user */
|
/*Deserializes uint64_t into 4 uint16_t, freeing out is left to the user */
|
||||||
/**************************************************************************/
|
/**************************************************************************/
|
||||||
uint16_t* u64_cvt_u16(uint64_t u64){
|
uint16_t* u64_cvt_u16(uint64_t u64) {
|
||||||
uint16_t* out = new uint16_t[4];
|
uint16_t* out = new uint16_t[4];
|
||||||
uint32_t int32_1 = u64 & 0xFFFFFFFF;
|
uint32_t int32_1 = u64 & 0xFFFFFFFF;
|
||||||
uint32_t int32_2 = (u64 & 0xFFFFFFFF00000000 ) >> 32;
|
uint32_t int32_2 = (u64 & 0xFFFFFFFF00000000) >> 32;
|
||||||
out[0] = int32_1 & 0xFFFF;
|
out[0] = int32_1 & 0xFFFF;
|
||||||
out[1] = (int32_1 & (0xFFFF0000) ) >> 16;
|
out[1] = (int32_1 & (0xFFFF0000)) >> 16;
|
||||||
out[2] = int32_2 & 0xFFFF;
|
out[2] = int32_2 & 0xFFFF;
|
||||||
out[3] = (int32_2 & (0xFFFF0000) ) >> 16;
|
out[3] = (int32_2 & (0xFFFF0000)) >> 16;
|
||||||
//cout << " values " <<out[0] <<" "<<out[1] <<" "<<out[2] <<" "<<out[3] <<" ";
|
//cout << " values " <<out[0] <<" "<<out[1] <<" "<<out[2] <<" "<<out[3] <<" ";
|
||||||
return out;
|
return out;
|
||||||
}
|
}
|
||||||
|
|
||||||
/***************************************************/
|
/***************************************************/
|
||||||
/*Appends obtained messages to buzz in message Queue*/
|
/*Appends obtained messages to buzz in message Queue*/
|
||||||
/***************************************************/
|
/***************************************************/
|
||||||
|
|
||||||
/*******************************************************************************************************************/
|
/*******************************************************************************************************************/
|
||||||
/* Message format of payload (Each slot is uint64_t) */
|
/* Message format of payload (Each slot is uint64_t) */
|
||||||
/* _______________________________________________________________________________________________________________ */
|
/* _______________________________________________________________________________________________________________ */
|
||||||
/*| | |*/
|
/*| | |*/
|
||||||
/*|Size in Uint64_t(but size is Uint16_t)|robot_id|Update msg size|Update msg|Update msgs+Buzz_msgs with size.....|*/
|
/*|Size in Uint64_t(but size is Uint16_t)|robot_id|Update msg size|Update msg|Update msgs+Buzz_msgs with size.....|*/
|
||||||
/*|__________________________________________________________________________|____________________________________|*/
|
/*|__________________________________________________________________________|____________________________________|*/
|
||||||
/*******************************************************************************************************************/
|
/*******************************************************************************************************************/
|
||||||
|
|
||||||
void in_msg_process(uint64_t* payload){
|
void in_msg_process(uint64_t* payload) {
|
||||||
|
|
||||||
/* Go through messages and add them to the FIFO */
|
/* Go through messages and add them to the FIFO */
|
||||||
uint16_t* data= u64_cvt_u16((uint64_t)payload[0]);
|
uint16_t* data = u64_cvt_u16((uint64_t) payload[0]);
|
||||||
/*Size is at first 2 bytes*/
|
/*Size is at first 2 bytes*/
|
||||||
uint16_t size=data[0]*sizeof(uint64_t);
|
uint16_t size = data[0] * sizeof(uint64_t);
|
||||||
delete[] data;
|
delete[] data;
|
||||||
uint8_t* pl =(uint8_t*)malloc(size);
|
uint8_t* pl = (uint8_t*) malloc(size);
|
||||||
memset(pl, 0,size);
|
memset(pl, 0, size);
|
||||||
/* Copy packet into temporary buffer */
|
/* Copy packet into temporary buffer */
|
||||||
memcpy(pl, payload ,size);
|
memcpy(pl, payload, size);
|
||||||
/*size and robot id read*/
|
/*size and robot id read*/
|
||||||
size_t tot = sizeof(uint32_t);
|
size_t tot = sizeof(uint32_t);
|
||||||
/*for(int i=0;i<data[0];i++){
|
/*for(int i=0;i<data[0];i++){
|
||||||
@ -84,7 +81,7 @@ namespace buzz_utility{
|
|||||||
}*/
|
}*/
|
||||||
/* Go through the messages until there's nothing else to read */
|
/* Go through the messages until there's nothing else to read */
|
||||||
//fprintf(stdout,"Total data size : utils : %d\n",(int)size);
|
//fprintf(stdout,"Total data size : utils : %d\n",(int)size);
|
||||||
uint16_t unMsgSize=0;
|
uint16_t unMsgSize = 0;
|
||||||
//uint8_t is_msg_pres=*(uint8_t*)(pl + tot);
|
//uint8_t is_msg_pres=*(uint8_t*)(pl + tot);
|
||||||
//tot+=sizeof(uint8_t);
|
//tot+=sizeof(uint8_t);
|
||||||
//fprintf(stdout,"is_updater msg present : %i\n",(int)is_msg_pres);
|
//fprintf(stdout,"is_updater msg present : %i\n",(int)is_msg_pres);
|
||||||
@ -105,31 +102,31 @@ namespace buzz_utility{
|
|||||||
/*Obtain Buzz messages only when they are present*/
|
/*Obtain Buzz messages only when they are present*/
|
||||||
do {
|
do {
|
||||||
/* Get payload size */
|
/* Get payload size */
|
||||||
unMsgSize = *(uint16_t*)(pl + tot);
|
unMsgSize = *(uint16_t*) (pl + tot);
|
||||||
tot += sizeof(uint16_t);
|
tot += sizeof(uint16_t);
|
||||||
/* Append message to the Buzz input message queue */
|
/* Append message to the Buzz input message queue */
|
||||||
if(unMsgSize > 0 && unMsgSize <= size - tot ) {
|
if (unMsgSize > 0 && unMsgSize <= size - tot) {
|
||||||
buzzinmsg_queue_append(VM,
|
buzzinmsg_queue_append(VM,
|
||||||
buzzmsg_payload_frombuffer(pl +tot, unMsgSize));
|
buzzmsg_payload_frombuffer(pl + tot, unMsgSize));
|
||||||
tot += unMsgSize;
|
tot += unMsgSize;
|
||||||
}
|
}
|
||||||
}while(size - tot > sizeof(uint16_t) && unMsgSize > 0);
|
} while (size - tot > sizeof(uint16_t) && unMsgSize > 0);
|
||||||
delete[] pl;
|
delete[] pl;
|
||||||
/* Process messages */
|
/* Process messages */
|
||||||
buzzvm_process_inmsgs(VM);
|
buzzvm_process_inmsgs(VM);
|
||||||
}
|
}
|
||||||
/***************************************************/
|
/***************************************************/
|
||||||
/*Obtains messages from buzz out message Queue*/
|
/*Obtains messages from buzz out message Queue*/
|
||||||
/***************************************************/
|
/***************************************************/
|
||||||
|
|
||||||
uint64_t* out_msg_process(){
|
uint64_t* out_msg_process() {
|
||||||
buzzvm_process_outmsgs(VM);
|
buzzvm_process_outmsgs(VM);
|
||||||
uint8_t* buff_send =(uint8_t*)malloc(MAX_MSG_SIZE);
|
uint8_t* buff_send = (uint8_t*) malloc(MAX_MSG_SIZE);
|
||||||
memset(buff_send, 0, MAX_MSG_SIZE);
|
memset(buff_send, 0, MAX_MSG_SIZE);
|
||||||
/*Taking into consideration the sizes included at the end*/
|
/*Taking into consideration the sizes included at the end*/
|
||||||
ssize_t tot = sizeof(uint16_t);
|
ssize_t tot = sizeof(uint16_t);
|
||||||
/* Send robot id */
|
/* Send robot id */
|
||||||
*(uint16_t*)(buff_send+tot) = (uint16_t) VM->robot;
|
*(uint16_t*) (buff_send + tot) = (uint16_t) VM->robot;
|
||||||
tot += sizeof(uint16_t);
|
tot += sizeof(uint16_t);
|
||||||
//uint8_t updater_msg_pre = 0;
|
//uint8_t updater_msg_pre = 0;
|
||||||
//uint16_t updater_msgSize= 0;
|
//uint16_t updater_msgSize= 0;
|
||||||
@ -158,19 +155,18 @@ namespace buzz_utility{
|
|||||||
/* Send messages from FIFO */
|
/* Send messages from FIFO */
|
||||||
do {
|
do {
|
||||||
/* Are there more messages? */
|
/* Are there more messages? */
|
||||||
if(buzzoutmsg_queue_isempty(VM)) break;
|
if (buzzoutmsg_queue_isempty(VM))
|
||||||
|
break;
|
||||||
/* Get first message */
|
/* Get first message */
|
||||||
buzzmsg_payload_t m = buzzoutmsg_queue_first(VM);
|
buzzmsg_payload_t m = buzzoutmsg_queue_first(VM);
|
||||||
/* Make sure the next message makes the data buffer with buzz messages to be less than 100 Bytes */
|
/* Make sure the next message makes the data buffer with buzz messages to be less than 100 Bytes */
|
||||||
if(tot + buzzmsg_payload_size(m) + sizeof(uint16_t)
|
if (tot + buzzmsg_payload_size(m) + sizeof(uint16_t) > MSG_SIZE) {
|
||||||
>
|
|
||||||
MSG_SIZE) {
|
|
||||||
buzzmsg_payload_destroy(&m);
|
buzzmsg_payload_destroy(&m);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
/* Add message length to data buffer */
|
/* Add message length to data buffer */
|
||||||
*(uint16_t*)(buff_send + tot) = (uint16_t)buzzmsg_payload_size(m);
|
*(uint16_t*) (buff_send + tot) = (uint16_t) buzzmsg_payload_size(m);
|
||||||
tot += sizeof(uint16_t);
|
tot += sizeof(uint16_t);
|
||||||
|
|
||||||
/* Add payload to data buffer */
|
/* Add payload to data buffer */
|
||||||
@ -180,291 +176,290 @@ namespace buzz_utility{
|
|||||||
/* Get rid of message */
|
/* Get rid of message */
|
||||||
buzzoutmsg_queue_next(VM);
|
buzzoutmsg_queue_next(VM);
|
||||||
buzzmsg_payload_destroy(&m);
|
buzzmsg_payload_destroy(&m);
|
||||||
} while(1);
|
} while (1);
|
||||||
|
|
||||||
uint16_t total_size =(ceil((float)tot/(float)sizeof(uint64_t)));
|
uint16_t total_size = (ceil((float) tot / (float) sizeof(uint64_t)));
|
||||||
*(uint16_t*)buff_send = (uint16_t) total_size;
|
*(uint16_t*) buff_send = (uint16_t) total_size;
|
||||||
|
|
||||||
uint64_t* payload_64 = new uint64_t[total_size];
|
uint64_t* payload_64 = new uint64_t[total_size];
|
||||||
|
|
||||||
memcpy((void*)payload_64, (void*)buff_send, total_size*sizeof(uint64_t));
|
memcpy((void*) payload_64, (void*) buff_send, total_size * sizeof(uint64_t));
|
||||||
delete[] buff_send;
|
delete[] buff_send;
|
||||||
/*for(int i=0;i<total_size;i++){
|
/*for(int i=0;i<total_size;i++){
|
||||||
cout<<" payload from out msg "<<*(payload_64+i)<<endl;
|
cout<<" payload from out msg "<<*(payload_64+i)<<endl;
|
||||||
}*/
|
}*/
|
||||||
/* Send message */
|
/* Send message */
|
||||||
return payload_64;
|
return payload_64;
|
||||||
}
|
}
|
||||||
|
|
||||||
/****************************************/
|
/****************************************/
|
||||||
/*Buzz script not able to load*/
|
/*Buzz script not able to load*/
|
||||||
/****************************************/
|
/****************************************/
|
||||||
|
|
||||||
static const char* buzz_error_info() {
|
static const char* buzz_error_info() {
|
||||||
buzzdebug_entry_t dbg = *buzzdebug_info_get_fromoffset(DBG_INFO, &VM->pc);
|
buzzdebug_entry_t dbg = *buzzdebug_info_get_fromoffset(DBG_INFO, &VM->pc);
|
||||||
char* msg;
|
char* msg;
|
||||||
if(dbg != NULL) {
|
if (dbg != NULL) {
|
||||||
asprintf(&msg,
|
asprintf (&msg,
|
||||||
"%s: execution terminated abnormally at %s:%" PRIu64 ":%" PRIu64 " : %s\n\n",
|
"%s: execution terminated abnormally at %s:%" PRIu64 ":%" PRIu64 " : %s\n\n",
|
||||||
BO_FNAME,
|
BO_FNAME,
|
||||||
dbg->fname,
|
dbg->fname,
|
||||||
dbg->line,
|
dbg->line,
|
||||||
dbg->col,
|
dbg->col,
|
||||||
VM->errormsg);
|
VM->errormsg);
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
asprintf(&msg,
|
asprintf(&msg,
|
||||||
"%s: execution terminated abnormally at bytecode offset %d: %s\n\n",
|
"%s: execution terminated abnormally at bytecode offset %d: %s\n\n",
|
||||||
BO_FNAME,
|
BO_FNAME,
|
||||||
VM->pc,
|
VM->pc,
|
||||||
VM->errormsg);
|
VM->errormsg);
|
||||||
}
|
}
|
||||||
return msg;
|
return msg;
|
||||||
}
|
}
|
||||||
|
|
||||||
/****************************************/
|
/****************************************/
|
||||||
/*Buzz hooks that can be used inside .bzz file*/
|
/*Buzz hooks that can be used inside .bzz file*/
|
||||||
/****************************************/
|
/****************************************/
|
||||||
|
|
||||||
static int buzz_register_hooks() {
|
static int buzz_register_hooks() {
|
||||||
buzzvm_pushs(VM, buzzvm_string_register(VM, "print", 1));
|
buzzvm_pushs(VM, buzzvm_string_register(VM, "print", 1));
|
||||||
buzzvm_pushcc(VM, buzzvm_function_register(VM, buzzuav_closures::buzzros_print));
|
buzzvm_pushcc(VM, buzzvm_function_register(VM, buzzuav_closures::buzzros_print));
|
||||||
buzzvm_gstore(VM);
|
buzzvm_gstore(VM);
|
||||||
buzzvm_pushs(VM, buzzvm_string_register(VM, "log", 1));
|
buzzvm_pushs(VM, buzzvm_string_register(VM, "log", 1));
|
||||||
buzzvm_pushcc(VM, buzzvm_function_register(VM, buzzuav_closures::buzzros_print));
|
buzzvm_pushcc(VM, buzzvm_function_register(VM, buzzuav_closures::buzzros_print));
|
||||||
buzzvm_gstore(VM);
|
buzzvm_gstore(VM);
|
||||||
buzzvm_pushs(VM, buzzvm_string_register(VM, "uav_moveto", 1));
|
buzzvm_pushs(VM, buzzvm_string_register(VM, "uav_moveto", 1));
|
||||||
buzzvm_pushcc(VM, buzzvm_function_register(VM, buzzuav_closures::buzzuav_moveto));
|
buzzvm_pushcc(VM, buzzvm_function_register(VM, buzzuav_closures::buzzuav_moveto));
|
||||||
buzzvm_gstore(VM);
|
buzzvm_gstore(VM);
|
||||||
buzzvm_pushs(VM, buzzvm_string_register(VM, "uav_goto", 1));
|
buzzvm_pushs(VM, buzzvm_string_register(VM, "uav_goto", 1));
|
||||||
buzzvm_pushcc(VM, buzzvm_function_register(VM, buzzuav_closures::buzzuav_goto));
|
buzzvm_pushcc(VM, buzzvm_function_register(VM, buzzuav_closures::buzzuav_goto));
|
||||||
buzzvm_gstore(VM);
|
buzzvm_gstore(VM);
|
||||||
buzzvm_pushs(VM, buzzvm_string_register(VM, "uav_takeoff", 1));
|
buzzvm_pushs(VM, buzzvm_string_register(VM, "uav_takeoff", 1));
|
||||||
buzzvm_pushcc(VM, buzzvm_function_register(VM, buzzuav_closures::buzzuav_takeoff));
|
buzzvm_pushcc(VM, buzzvm_function_register(VM, buzzuav_closures::buzzuav_takeoff));
|
||||||
buzzvm_gstore(VM);
|
buzzvm_gstore(VM);
|
||||||
buzzvm_pushs(VM, buzzvm_string_register(VM, "uav_gohome", 1));
|
buzzvm_pushs(VM, buzzvm_string_register(VM, "uav_gohome", 1));
|
||||||
buzzvm_pushcc(VM, buzzvm_function_register(VM, buzzuav_closures::buzzuav_gohome));
|
buzzvm_pushcc(VM, buzzvm_function_register(VM, buzzuav_closures::buzzuav_gohome));
|
||||||
buzzvm_gstore(VM);
|
buzzvm_gstore(VM);
|
||||||
buzzvm_pushs(VM, buzzvm_string_register(VM, "uav_land", 1));
|
buzzvm_pushs(VM, buzzvm_string_register(VM, "uav_land", 1));
|
||||||
buzzvm_pushcc(VM, buzzvm_function_register(VM, buzzuav_closures::buzzuav_land));
|
buzzvm_pushcc(VM, buzzvm_function_register(VM, buzzuav_closures::buzzuav_land));
|
||||||
buzzvm_gstore(VM);
|
buzzvm_gstore(VM);
|
||||||
return BUZZVM_STATE_READY;
|
return BUZZVM_STATE_READY;
|
||||||
}
|
}
|
||||||
|
|
||||||
/**************************************************/
|
/**************************************************/
|
||||||
/*Register dummy Buzz hooks for test during update*/
|
/*Register dummy Buzz hooks for test during update*/
|
||||||
/**************************************************/
|
/**************************************************/
|
||||||
|
|
||||||
static int testing_buzz_register_hooks() {
|
static int testing_buzz_register_hooks() {
|
||||||
buzzvm_pushs(VM, buzzvm_string_register(VM, "print", 1));
|
buzzvm_pushs(VM, buzzvm_string_register(VM, "print", 1));
|
||||||
buzzvm_pushcc(VM, buzzvm_function_register(VM, buzzuav_closures::buzzros_print));
|
buzzvm_pushcc(VM, buzzvm_function_register(VM, buzzuav_closures::buzzros_print));
|
||||||
buzzvm_gstore(VM);
|
buzzvm_gstore(VM);
|
||||||
buzzvm_pushs(VM, buzzvm_string_register(VM, "log", 1));
|
buzzvm_pushs(VM, buzzvm_string_register(VM, "log", 1));
|
||||||
buzzvm_pushcc(VM, buzzvm_function_register(VM, buzzuav_closures::buzzros_print));
|
buzzvm_pushcc(VM, buzzvm_function_register(VM, buzzuav_closures::buzzros_print));
|
||||||
buzzvm_gstore(VM);
|
buzzvm_gstore(VM);
|
||||||
buzzvm_pushs(VM, buzzvm_string_register(VM, "uav_moveto", 1));
|
buzzvm_pushs(VM, buzzvm_string_register(VM, "uav_moveto", 1));
|
||||||
buzzvm_pushcc(VM, buzzvm_function_register(VM, buzzuav_closures::dummy_closure));
|
buzzvm_pushcc(VM, buzzvm_function_register(VM, buzzuav_closures::dummy_closure));
|
||||||
buzzvm_gstore(VM);
|
buzzvm_gstore(VM);
|
||||||
buzzvm_pushs(VM, buzzvm_string_register(VM, "uav_goto", 1));
|
buzzvm_pushs(VM, buzzvm_string_register(VM, "uav_goto", 1));
|
||||||
buzzvm_pushcc(VM, buzzvm_function_register(VM, buzzuav_closures::dummy_closure));
|
buzzvm_pushcc(VM, buzzvm_function_register(VM, buzzuav_closures::dummy_closure));
|
||||||
buzzvm_gstore(VM);
|
buzzvm_gstore(VM);
|
||||||
buzzvm_pushs(VM, buzzvm_string_register(VM, "uav_takeoff", 1));
|
buzzvm_pushs(VM, buzzvm_string_register(VM, "uav_takeoff", 1));
|
||||||
buzzvm_pushcc(VM, buzzvm_function_register(VM, buzzuav_closures::dummy_closure));
|
buzzvm_pushcc(VM, buzzvm_function_register(VM, buzzuav_closures::dummy_closure));
|
||||||
buzzvm_gstore(VM);
|
buzzvm_gstore(VM);
|
||||||
buzzvm_pushs(VM, buzzvm_string_register(VM, "uav_gohome", 1));
|
buzzvm_pushs(VM, buzzvm_string_register(VM, "uav_gohome", 1));
|
||||||
buzzvm_pushcc(VM, buzzvm_function_register(VM, buzzuav_closures::dummy_closure));
|
buzzvm_pushcc(VM, buzzvm_function_register(VM, buzzuav_closures::dummy_closure));
|
||||||
buzzvm_gstore(VM);
|
buzzvm_gstore(VM);
|
||||||
buzzvm_pushs(VM, buzzvm_string_register(VM, "uav_land", 1));
|
buzzvm_pushs(VM, buzzvm_string_register(VM, "uav_land", 1));
|
||||||
buzzvm_pushcc(VM, buzzvm_function_register(VM, buzzuav_closures::dummy_closure));
|
buzzvm_pushcc(VM, buzzvm_function_register(VM, buzzuav_closures::dummy_closure));
|
||||||
buzzvm_gstore(VM);
|
buzzvm_gstore(VM);
|
||||||
return BUZZVM_STATE_READY;
|
return BUZZVM_STATE_READY;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/****************************************/
|
||||||
|
/*Sets the .bzz and .bdbg file*/
|
||||||
|
/****************************************/
|
||||||
|
|
||||||
/****************************************/
|
int buzz_script_set(const char* bo_filename,
|
||||||
/*Sets the .bzz and .bdbg file*/
|
|
||||||
/****************************************/
|
|
||||||
|
|
||||||
int buzz_script_set(const char* bo_filename,
|
|
||||||
const char* bdbg_filename, int robot_id) {
|
const char* bdbg_filename, int robot_id) {
|
||||||
//cout<<"bo file name"<<bo_filename;
|
//cout<<"bo file name"<<bo_filename;
|
||||||
/* Get hostname */
|
/* Get hostname */
|
||||||
char hstnm[30];
|
char hstnm[30];
|
||||||
//char* hstnm ="M1003";
|
//char* hstnm ="M1003";
|
||||||
gethostname(hstnm, 30);
|
gethostname(hstnm, 30);
|
||||||
/* Make numeric id from hostname */
|
/* Make numeric id from hostname */
|
||||||
/* NOTE: here we assume that the hostname is in the format Knn */
|
/* NOTE: here we assume that the hostname is in the format Knn */
|
||||||
int id = strtol(hstnm+4, NULL, 10);
|
int id = strtol(hstnm+4, NULL, 10);
|
||||||
cout << " Robot ID: " <<id<< endl;
|
cout << " Robot ID: " <<id<< endl;
|
||||||
/* Reset the Buzz VM */
|
/* Reset the Buzz VM */
|
||||||
if(VM) buzzvm_destroy(&VM);
|
if(VM) buzzvm_destroy(&VM);
|
||||||
VM = buzzvm_new((int)id);
|
VM = buzzvm_new((int)id);
|
||||||
/* Get rid of debug info */
|
/* Get rid of debug info */
|
||||||
if(DBG_INFO) buzzdebug_destroy(&DBG_INFO);
|
if(DBG_INFO) buzzdebug_destroy(&DBG_INFO);
|
||||||
DBG_INFO = buzzdebug_new();
|
DBG_INFO = buzzdebug_new();
|
||||||
/* Read bytecode and fill in data structure */
|
/* Read bytecode and fill in data structure */
|
||||||
FILE* fd = fopen(bo_filename, "rb");
|
FILE* fd = fopen(bo_filename, "rb");
|
||||||
if(!fd) {
|
if(!fd) {
|
||||||
perror(bo_filename);
|
perror(bo_filename);
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
fseek(fd, 0, SEEK_END);
|
fseek(fd, 0, SEEK_END);
|
||||||
size_t bcode_size = ftell(fd);
|
size_t bcode_size = ftell(fd);
|
||||||
rewind(fd);
|
rewind(fd);
|
||||||
BO_BUF = (uint8_t*)malloc(bcode_size);
|
BO_BUF = (uint8_t*)malloc(bcode_size);
|
||||||
if(fread(BO_BUF, 1, bcode_size, fd) < bcode_size) {
|
if(fread(BO_BUF, 1, bcode_size, fd) < bcode_size) {
|
||||||
perror(bo_filename);
|
perror(bo_filename);
|
||||||
buzzvm_destroy(&VM);
|
buzzvm_destroy(&VM);
|
||||||
buzzdebug_destroy(&DBG_INFO);
|
buzzdebug_destroy(&DBG_INFO);
|
||||||
fclose(fd);
|
fclose(fd);
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
fclose(fd);
|
fclose(fd);
|
||||||
/* Read debug information */
|
/* Read debug information */
|
||||||
//if(!buzzdebug_fromfile(DBG_INFO, bdbg_filename)) {
|
//if(!buzzdebug_fromfile(DBG_INFO, bdbg_filename)) {
|
||||||
// buzzvm_destroy(&VM);
|
// buzzvm_destroy(&VM);
|
||||||
// buzzdebug_destroy(&DBG_INFO);
|
// buzzdebug_destroy(&DBG_INFO);
|
||||||
// perror(bdbg_filename);
|
// perror(bdbg_filename);
|
||||||
// return 0;
|
// return 0;
|
||||||
//}
|
//}
|
||||||
/* Set byte code */
|
/* Set byte code */
|
||||||
//if(buzzvm_set_bcode(VM, BO_BUF, bcode_size) != BUZZVM_STATE_READY) {
|
//if(buzzvm_set_bcode(VM, BO_BUF, bcode_size) != BUZZVM_STATE_READY) {
|
||||||
// buzzvm_destroy(&VM);
|
// buzzvm_destroy(&VM);
|
||||||
// buzzdebug_destroy(&DBG_INFO);
|
// buzzdebug_destroy(&DBG_INFO);
|
||||||
// fprintf(stdout, "%s: Error loading Buzz script\n\n", bo_filename);
|
// fprintf(stdout, "%s: Error loading Buzz script\n\n", bo_filename);
|
||||||
// return 0;
|
// return 0;
|
||||||
//}
|
//}
|
||||||
/* Register hook functions */
|
/* Register hook functions */
|
||||||
/*if(buzz_register_hooks() != BUZZVM_STATE_READY) {
|
/*if(buzz_register_hooks() != BUZZVM_STATE_READY) {
|
||||||
buzzvm_destroy(&VM);
|
buzzvm_destroy(&VM);
|
||||||
buzzdebug_destroy(&DBG_INFO);
|
buzzdebug_destroy(&DBG_INFO);
|
||||||
fprintf(stdout, "%s: Error registering hooks\n\n", bo_filename);
|
fprintf(stdout, "%s: Error registering hooks\n\n", bo_filename);
|
||||||
return 0;
|
return 0;
|
||||||
}*/
|
}*/
|
||||||
/* Save bytecode file name */
|
/* Save bytecode file name */
|
||||||
//BO_FNAME = strdup(bo_filename);
|
//BO_FNAME = strdup(bo_filename);
|
||||||
/* Execute the global part of the script */
|
/* Execute the global part of the script */
|
||||||
//buzzvm_execute_script(VM);
|
//buzzvm_execute_script(VM);
|
||||||
/* Call the Init() function */
|
/* Call the Init() function */
|
||||||
//buzzvm_function_call(VM, "init", 0);
|
//buzzvm_function_call(VM, "init", 0);
|
||||||
/* All OK */
|
/* All OK */
|
||||||
return buzz_update_set(BO_BUF, bdbg_filename, bcode_size);
|
return buzz_update_set(BO_BUF, bdbg_filename, bcode_size);
|
||||||
}
|
}
|
||||||
|
|
||||||
/****************************************/
|
/****************************************/
|
||||||
/*Sets a new update */
|
/*Sets a new update */
|
||||||
/****************************************/
|
/****************************************/
|
||||||
int buzz_update_set(uint8_t* UP_BO_BUF, const char* bdbg_filename,size_t bcode_size){
|
int buzz_update_set(uint8_t* UP_BO_BUF, const char* bdbg_filename,size_t bcode_size) {
|
||||||
/* Get hostname */
|
/* Get hostname */
|
||||||
char hstnm[30];
|
char hstnm[30];
|
||||||
gethostname(hstnm, 30);
|
gethostname(hstnm, 30);
|
||||||
/* Make numeric id from hostname */
|
/* Make numeric id from hostname */
|
||||||
/* NOTE: here we assume that the hostname is in the format Knn */
|
/* NOTE: here we assume that the hostname is in the format Knn */
|
||||||
int id = strtol(hstnm + 4, NULL, 10);
|
int id = strtol(hstnm + 4, NULL, 10);
|
||||||
|
|
||||||
/* Reset the Buzz VM */
|
/* Reset the Buzz VM */
|
||||||
if(VM) buzzvm_destroy(&VM);
|
if(VM) buzzvm_destroy(&VM);
|
||||||
VM = buzzvm_new(id);
|
VM = buzzvm_new(id);
|
||||||
/* Get rid of debug info */
|
/* Get rid of debug info */
|
||||||
if(DBG_INFO) buzzdebug_destroy(&DBG_INFO);
|
if(DBG_INFO) buzzdebug_destroy(&DBG_INFO);
|
||||||
DBG_INFO = buzzdebug_new();
|
DBG_INFO = buzzdebug_new();
|
||||||
|
|
||||||
/* Read debug information */
|
/* Read debug information */
|
||||||
if(!buzzdebug_fromfile(DBG_INFO, bdbg_filename)) {
|
if(!buzzdebug_fromfile(DBG_INFO, bdbg_filename)) {
|
||||||
buzzvm_destroy(&VM);
|
buzzvm_destroy(&VM);
|
||||||
buzzdebug_destroy(&DBG_INFO);
|
buzzdebug_destroy(&DBG_INFO);
|
||||||
perror(bdbg_filename);
|
perror(bdbg_filename);
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
/* Set byte code */
|
/* Set byte code */
|
||||||
if(buzzvm_set_bcode(VM, UP_BO_BUF, bcode_size) != BUZZVM_STATE_READY) {
|
if(buzzvm_set_bcode(VM, UP_BO_BUF, bcode_size) != BUZZVM_STATE_READY) {
|
||||||
buzzvm_destroy(&VM);
|
buzzvm_destroy(&VM);
|
||||||
buzzdebug_destroy(&DBG_INFO);
|
buzzdebug_destroy(&DBG_INFO);
|
||||||
fprintf(stdout, "%s: Error loading Buzz script\n\n", BO_FNAME);
|
fprintf(stdout, "%s: Error loading Buzz script\n\n", BO_FNAME);
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
/* Register hook functions */
|
/* Register hook functions */
|
||||||
if(buzz_register_hooks() != BUZZVM_STATE_READY) {
|
if(buzz_register_hooks() != BUZZVM_STATE_READY) {
|
||||||
buzzvm_destroy(&VM);
|
buzzvm_destroy(&VM);
|
||||||
buzzdebug_destroy(&DBG_INFO);
|
buzzdebug_destroy(&DBG_INFO);
|
||||||
fprintf(stdout, "%s: Error registering hooks\n\n", BO_FNAME);
|
fprintf(stdout, "%s: Error registering hooks\n\n", BO_FNAME);
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
/* Execute the global part of the script */
|
/* Execute the global part of the script */
|
||||||
buzzvm_execute_script(VM);
|
buzzvm_execute_script(VM);
|
||||||
/* Call the Init() function */
|
/* Call the Init() function */
|
||||||
buzzvm_function_call(VM, "init", 0);
|
buzzvm_function_call(VM, "init", 0);
|
||||||
/* All OK */
|
/* All OK */
|
||||||
return 1;
|
return 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
/****************************************/
|
/****************************************/
|
||||||
/*Performs a initialization test */
|
/*Performs a initialization test */
|
||||||
/****************************************/
|
/****************************************/
|
||||||
int buzz_update_init_test(uint8_t* UP_BO_BUF, const char* bdbg_filename,size_t bcode_size){
|
int buzz_update_init_test(uint8_t* UP_BO_BUF, const char* bdbg_filename,size_t bcode_size) {
|
||||||
/* Get hostname */
|
/* Get hostname */
|
||||||
char hstnm[30];
|
char hstnm[30];
|
||||||
gethostname(hstnm, 30);
|
gethostname(hstnm, 30);
|
||||||
/* Make numeric id from hostname */
|
/* Make numeric id from hostname */
|
||||||
/* NOTE: here we assume that the hostname is in the format Knn */
|
/* NOTE: here we assume that the hostname is in the format Knn */
|
||||||
int id = strtol(hstnm + 4, NULL, 10);
|
int id = strtol(hstnm + 4, NULL, 10);
|
||||||
/* Reset the Buzz VM */
|
/* Reset the Buzz VM */
|
||||||
if(VM) buzzvm_destroy(&VM);
|
if(VM) buzzvm_destroy(&VM);
|
||||||
VM = buzzvm_new(id);
|
VM = buzzvm_new(id);
|
||||||
/* Get rid of debug info */
|
/* Get rid of debug info */
|
||||||
if(DBG_INFO) buzzdebug_destroy(&DBG_INFO);
|
if(DBG_INFO) buzzdebug_destroy(&DBG_INFO);
|
||||||
DBG_INFO = buzzdebug_new();
|
DBG_INFO = buzzdebug_new();
|
||||||
|
|
||||||
/* Read debug information */
|
/* Read debug information */
|
||||||
if(!buzzdebug_fromfile(DBG_INFO, bdbg_filename)) {
|
if(!buzzdebug_fromfile(DBG_INFO, bdbg_filename)) {
|
||||||
buzzvm_destroy(&VM);
|
buzzvm_destroy(&VM);
|
||||||
buzzdebug_destroy(&DBG_INFO);
|
buzzdebug_destroy(&DBG_INFO);
|
||||||
perror(bdbg_filename);
|
perror(bdbg_filename);
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
/* Set byte code */
|
/* Set byte code */
|
||||||
if(buzzvm_set_bcode(VM, UP_BO_BUF, bcode_size) != BUZZVM_STATE_READY) {
|
if(buzzvm_set_bcode(VM, UP_BO_BUF, bcode_size) != BUZZVM_STATE_READY) {
|
||||||
buzzvm_destroy(&VM);
|
buzzvm_destroy(&VM);
|
||||||
buzzdebug_destroy(&DBG_INFO);
|
buzzdebug_destroy(&DBG_INFO);
|
||||||
fprintf(stdout, "%s: Error loading Buzz script\n\n", BO_FNAME);
|
fprintf(stdout, "%s: Error loading Buzz script\n\n", BO_FNAME);
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
/* Register hook functions */
|
/* Register hook functions */
|
||||||
if(testing_buzz_register_hooks() != BUZZVM_STATE_READY) {
|
if(testing_buzz_register_hooks() != BUZZVM_STATE_READY) {
|
||||||
buzzvm_destroy(&VM);
|
buzzvm_destroy(&VM);
|
||||||
buzzdebug_destroy(&DBG_INFO);
|
buzzdebug_destroy(&DBG_INFO);
|
||||||
fprintf(stdout, "%s: Error registering hooks\n\n", BO_FNAME);
|
fprintf(stdout, "%s: Error registering hooks\n\n", BO_FNAME);
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
/* Execute the global part of the script */
|
/* Execute the global part of the script */
|
||||||
buzzvm_execute_script(VM);
|
buzzvm_execute_script(VM);
|
||||||
/* Call the Init() function */
|
/* Call the Init() function */
|
||||||
buzzvm_function_call(VM, "init", 0);
|
buzzvm_function_call(VM, "init", 0);
|
||||||
/* All OK */
|
/* All OK */
|
||||||
return 1;
|
return 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
/****************************************/
|
/****************************************/
|
||||||
/*Swarm struct*/
|
/*Swarm struct*/
|
||||||
/****************************************/
|
/****************************************/
|
||||||
|
|
||||||
struct buzzswarm_elem_s {
|
struct buzzswarm_elem_s {
|
||||||
buzzdarray_t swarms;
|
buzzdarray_t swarms;
|
||||||
uint16_t age;
|
uint16_t age;
|
||||||
};
|
};
|
||||||
typedef struct buzzswarm_elem_s* buzzswarm_elem_t;
|
typedef struct buzzswarm_elem_s* buzzswarm_elem_t;
|
||||||
|
|
||||||
void check_swarm_members(const void* key, void* data, void* params) {
|
void check_swarm_members(const void* key, void* data, void* params) {
|
||||||
buzzswarm_elem_t e = *(buzzswarm_elem_t*)data;
|
buzzswarm_elem_t e = *(buzzswarm_elem_t*)data;
|
||||||
int* status = (int*)params;
|
int* status = (int*)params;
|
||||||
if(*status == 3) return;
|
if(*status == 3) return;
|
||||||
if(buzzdarray_size(e->swarms) != 1) {
|
if(buzzdarray_size(e->swarms) != 1) {
|
||||||
fprintf(stderr, "Swarm list size is not 1\n");
|
fprintf(stderr, "Swarm list size is not 1\n");
|
||||||
*status = 3;
|
*status = 3;
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
int sid = 1;
|
int sid = 1;
|
||||||
if(*buzzdict_get(VM->swarms, &sid, uint8_t) &&
|
if(*buzzdict_get(VM->swarms, &sid, uint8_t) &&
|
||||||
buzzdarray_get(e->swarms, 0, uint16_t) != sid) {
|
buzzdarray_get(e->swarms, 0, uint16_t) != sid) {
|
||||||
@ -483,35 +478,35 @@ namespace buzz_utility{
|
|||||||
*status = 3;
|
*status = 3;
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
/*Step through the buzz script*/
|
/*Step through the buzz script*/
|
||||||
|
|
||||||
void buzz_script_step() {
|
void buzz_script_step() {
|
||||||
/*
|
/*
|
||||||
* Update sensors
|
* Update sensors
|
||||||
*/
|
*/
|
||||||
buzzuav_closures::buzzuav_update_battery(VM);
|
buzzuav_closures::buzzuav_update_battery(VM);
|
||||||
buzzuav_closures::buzzuav_update_prox(VM);
|
buzzuav_closures::buzzuav_update_prox(VM);
|
||||||
buzzuav_closures::buzzuav_update_currentpos(VM);
|
buzzuav_closures::buzzuav_update_currentpos(VM);
|
||||||
buzzuav_closures::buzzuav_update_flight_status(VM);
|
buzzuav_closures::buzzuav_update_flight_status(VM);
|
||||||
buzzuav_closures::buzzuav_update_obstacle(VM);
|
buzzuav_closures::buzzuav_update_obstacle(VM);
|
||||||
/*
|
/*
|
||||||
* Call Buzz step() function
|
* Call Buzz step() function
|
||||||
*/
|
*/
|
||||||
if(buzzvm_function_call(VM, "step", 0) != BUZZVM_STATE_READY) {
|
if(buzzvm_function_call(VM, "step", 0) != BUZZVM_STATE_READY) {
|
||||||
fprintf(stderr, "%s: execution terminated abnormally: %s\n\n",
|
fprintf(stderr, "%s: execution terminated abnormally: %s\n\n",
|
||||||
BO_FNAME,
|
BO_FNAME,
|
||||||
buzz_error_info());
|
buzz_error_info());
|
||||||
buzzvm_dump(VM);
|
buzzvm_dump(VM);
|
||||||
}
|
}
|
||||||
/*!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!*/
|
/*!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!*/
|
||||||
/* look into this currently we don't have swarm feature at all */
|
/* look into this currently we don't have swarm feature at all */
|
||||||
/*!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!*/
|
/*!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!*/
|
||||||
/*Print swarm*/
|
/*Print swarm*/
|
||||||
//buzzswarm_members_print(stdout, VM->swarmmembers, VM->robot);
|
//buzzswarm_members_print(stdout, VM->swarmmembers, VM->robot);
|
||||||
/* Check swarm state */
|
/* Check swarm state */
|
||||||
/* int status = 1;
|
/* int status = 1;
|
||||||
buzzdict_foreach(VM->swarmmembers, check_swarm_members, &status);
|
buzzdict_foreach(VM->swarmmembers, check_swarm_members, &status);
|
||||||
if(status == 1 &&
|
if(status == 1 &&
|
||||||
buzzdict_size(VM->swarmmembers) < 9)
|
buzzdict_size(VM->swarmmembers) < 9)
|
||||||
@ -519,14 +514,14 @@ namespace buzz_utility{
|
|||||||
buzzvm_pushs(VM, buzzvm_string_register(VM, "swarm_status", 1));
|
buzzvm_pushs(VM, buzzvm_string_register(VM, "swarm_status", 1));
|
||||||
buzzvm_pushi(VM, status);
|
buzzvm_pushi(VM, status);
|
||||||
buzzvm_gstore(VM);*/
|
buzzvm_gstore(VM);*/
|
||||||
}
|
}
|
||||||
|
|
||||||
/****************************************/
|
/****************************************/
|
||||||
/*Destroy the bvm and other resorces*/
|
/*Destroy the bvm and other resorces*/
|
||||||
/****************************************/
|
/****************************************/
|
||||||
|
|
||||||
void buzz_script_destroy() {
|
void buzz_script_destroy() {
|
||||||
if(VM) {
|
if(VM) {
|
||||||
if(VM->state != BUZZVM_STATE_READY) {
|
if(VM->state != BUZZVM_STATE_READY) {
|
||||||
fprintf(stderr, "%s: execution terminated abnormally: %s\n\n",
|
fprintf(stderr, "%s: execution terminated abnormally: %s\n\n",
|
||||||
BO_FNAME,
|
BO_FNAME,
|
||||||
@ -537,10 +532,9 @@ void buzz_script_destroy() {
|
|||||||
buzzvm_destroy(&VM);
|
buzzvm_destroy(&VM);
|
||||||
free(BO_FNAME);
|
free(BO_FNAME);
|
||||||
buzzdebug_destroy(&DBG_INFO);
|
buzzdebug_destroy(&DBG_INFO);
|
||||||
}
|
|
||||||
fprintf(stdout, "Script execution stopped.\n");
|
|
||||||
}
|
}
|
||||||
|
fprintf(stdout, "Script execution stopped.\n");
|
||||||
|
}
|
||||||
|
|
||||||
/****************************************/
|
/****************************************/
|
||||||
/****************************************/
|
/****************************************/
|
||||||
@ -550,10 +544,10 @@ void buzz_script_destroy() {
|
|||||||
/****************************************/
|
/****************************************/
|
||||||
|
|
||||||
int buzz_script_done() {
|
int buzz_script_done() {
|
||||||
return VM->state != BUZZVM_STATE_READY;
|
return VM->state != BUZZVM_STATE_READY;
|
||||||
}
|
}
|
||||||
|
|
||||||
int update_step_test(){
|
int update_step_test() {
|
||||||
|
|
||||||
buzzuav_closures::buzzuav_update_battery(VM);
|
buzzuav_closures::buzzuav_update_battery(VM);
|
||||||
buzzuav_closures::buzzuav_update_prox(VM);
|
buzzuav_closures::buzzuav_update_prox(VM);
|
||||||
@ -562,29 +556,27 @@ int update_step_test(){
|
|||||||
buzzuav_closures::buzzuav_update_obstacle(VM);
|
buzzuav_closures::buzzuav_update_obstacle(VM);
|
||||||
|
|
||||||
int a = buzzvm_function_call(VM, "step", 0);
|
int a = buzzvm_function_call(VM, "step", 0);
|
||||||
if(a != BUZZVM_STATE_READY){
|
if(a != BUZZVM_STATE_READY) {
|
||||||
fprintf(stdout, "step test VM state %i\n",a);
|
fprintf(stdout, "step test VM state %i\n",a);
|
||||||
fprintf(stdout, " execution terminated abnormally\n\n");
|
fprintf(stdout, " execution terminated abnormally\n\n");
|
||||||
}
|
}
|
||||||
return a == BUZZVM_STATE_READY;
|
return a == BUZZVM_STATE_READY;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint16_t get_robotid(){
|
uint16_t get_robotid() {
|
||||||
/* Get hostname */
|
/* Get hostname */
|
||||||
char hstnm[30];
|
char hstnm[30];
|
||||||
gethostname(hstnm, 30);
|
gethostname(hstnm, 30);
|
||||||
/* Make numeric id from hostname */
|
/* Make numeric id from hostname */
|
||||||
/* NOTE: here we assume that the hostname is in the format Knn */
|
/* NOTE: here we assume that the hostname is in the format Knn */
|
||||||
int id = strtol(hstnm + 4, NULL, 10);
|
int id = strtol(hstnm + 4, NULL, 10);
|
||||||
//fprintf(stdout, "Robot id from get rid buzz util: %i\n",id);
|
//fprintf(stdout, "Robot id from get rid buzz util: %i\n",id);
|
||||||
return (uint16_t)id;
|
return (uint16_t)id;
|
||||||
}
|
}
|
||||||
|
|
||||||
buzzvm_t get_vm(){
|
buzzvm_t get_vm() {
|
||||||
return VM;
|
return VM;
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
@ -238,7 +238,7 @@ namespace rosbzz_node{
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void roscontroller::WaypointMissionSetup(){
|
void roscontroller::WaypointMissionSetup(float lat, float lng, float alt){
|
||||||
mavros_msgs::WaypointPush srv;
|
mavros_msgs::WaypointPush srv;
|
||||||
mavros_msgs::Waypoint waypoint;
|
mavros_msgs::Waypoint waypoint;
|
||||||
|
|
||||||
@ -247,10 +247,9 @@ namespace rosbzz_node{
|
|||||||
waypoint.command = mavros_msgs::CommandCode::NAV_WAYPOINT;
|
waypoint.command = mavros_msgs::CommandCode::NAV_WAYPOINT;
|
||||||
waypoint.is_current = 2; // IMPORTANT: goto is no longer used, so instead, use magic number 2 for is_current parameter
|
waypoint.is_current = 2; // IMPORTANT: goto is no longer used, so instead, use magic number 2 for is_current parameter
|
||||||
waypoint.autocontinue = 0;
|
waypoint.autocontinue = 0;
|
||||||
waypoint.x_lat = 45.507730f;
|
waypoint.x_lat = lat;
|
||||||
waypoint.y_long = -73.613961f;
|
waypoint.y_long = lng;
|
||||||
//45.507730, -73.613961
|
waypoint.z_alt = alt;
|
||||||
waypoint.z_alt = 10;
|
|
||||||
|
|
||||||
srv.request.waypoints.push_back(waypoint);
|
srv.request.waypoints.push_back(waypoint);
|
||||||
if(mission_client.call(srv)){
|
if(mission_client.call(srv)){
|
||||||
@ -731,10 +730,10 @@ namespace rosbzz_node{
|
|||||||
ROS_INFO("RC_call: TAKE OFF!!!!");
|
ROS_INFO("RC_call: TAKE OFF!!!!");
|
||||||
rc_cmd=mavros_msgs::CommandCode::NAV_TAKEOFF;
|
rc_cmd=mavros_msgs::CommandCode::NAV_TAKEOFF;
|
||||||
/* arming */
|
/* arming */
|
||||||
SetMode("GUIDED", 0);
|
SetMode("LOITER", 0);
|
||||||
//SetMode("LOITER", 0);
|
//SetMode("GUIDED", 0);
|
||||||
cout << "this..." << endl;
|
cout << "this..." << endl;
|
||||||
//SetModeAsync("GUIDED", 5000);
|
SetModeAsync("GUIDED", 2000);
|
||||||
Arm();
|
Arm();
|
||||||
buzzuav_closures::rc_call(rc_cmd);
|
buzzuav_closures::rc_call(rc_cmd);
|
||||||
res.success = true;
|
res.success = true;
|
||||||
@ -754,12 +753,24 @@ namespace rosbzz_node{
|
|||||||
case mavros_msgs::CommandCode::NAV_WAYPOINT:
|
case mavros_msgs::CommandCode::NAV_WAYPOINT:
|
||||||
ROS_INFO("RC_Call: GO TO!!!! ");
|
ROS_INFO("RC_Call: GO TO!!!! ");
|
||||||
|
|
||||||
WaypointMissionSetup();
|
//WaypointMissionSetup();
|
||||||
|
|
||||||
double rc_goto[3];
|
double rc_goto[3];
|
||||||
rc_goto[0] = req.param5;
|
rc_goto[0] = req.param5;
|
||||||
rc_goto[1] = req.param6;
|
rc_goto[1] = req.param6;
|
||||||
rc_goto[2] = req.param7;
|
rc_goto[2] = req.param7;
|
||||||
|
|
||||||
|
WaypointMissionSetup(req.param5, req.param6, req.param7);
|
||||||
|
/*
|
||||||
|
WaypointMissionSetup(45.505293f, -73.614722f, 2.0f);
|
||||||
|
std::this_thread::sleep_for( std::chrono::milliseconds ( 100 ) );
|
||||||
|
WaypointMissionSetup(45.505324f, -73.614502f, 2.0f);
|
||||||
|
std::this_thread::sleep_for( std::chrono::milliseconds ( 100 ) );
|
||||||
|
WaypointMissionSetup(45.505452f, -73.614655f, 2.0f);
|
||||||
|
std::this_thread::sleep_for( std::chrono::milliseconds ( 100 ) );
|
||||||
|
WaypointMissionSetup(45.505463f, -73.614389f, 2.0f);
|
||||||
|
std::this_thread::sleep_for( std::chrono::milliseconds ( 100 ) );
|
||||||
|
*/
|
||||||
|
|
||||||
buzzuav_closures::rc_set_goto(rc_goto);
|
buzzuav_closures::rc_set_goto(rc_goto);
|
||||||
rc_cmd=mavros_msgs::CommandCode::NAV_WAYPOINT;
|
rc_cmd=mavros_msgs::CommandCode::NAV_WAYPOINT;
|
||||||
buzzuav_closures::rc_call(rc_cmd);
|
buzzuav_closures::rc_call(rc_cmd);
|
||||||
|
Loading…
Reference in New Issue
Block a user