changes in handshaking commuincation
This commit is contained in:
parent
225d561606
commit
c756bdf5fd
@ -123,4 +123,8 @@ void destroy_updater();
|
|||||||
|
|
||||||
int is_msg_present();
|
int is_msg_present();
|
||||||
|
|
||||||
|
int get_update_status();
|
||||||
|
|
||||||
|
void set_read_update_status();
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
@ -23,6 +23,8 @@
|
|||||||
#include "buzzuav_closures.h"
|
#include "buzzuav_closures.h"
|
||||||
|
|
||||||
#define UPDATER_MESSAGE_CONSTANT 987654321
|
#define UPDATER_MESSAGE_CONSTANT 987654321
|
||||||
|
#define XBEE_MESSAGE_CONSTANT 586782343
|
||||||
|
#define XBEE_STOP_TRANSMISSION 4355356352
|
||||||
|
|
||||||
using namespace std;
|
using namespace std;
|
||||||
|
|
||||||
@ -50,6 +52,7 @@ private:
|
|||||||
int barrier;
|
int barrier;
|
||||||
std::string bzzfile_name, fcclient_name, rcservice_name,bcfname,dbgfname,out_payload,in_payload,stand_by; //, rcclient;
|
std::string bzzfile_name, fcclient_name, rcservice_name,bcfname,dbgfname,out_payload,in_payload,stand_by; //, rcclient;
|
||||||
bool rcclient;
|
bool rcclient;
|
||||||
|
bool multi_msg;
|
||||||
ros::ServiceClient mav_client;
|
ros::ServiceClient mav_client;
|
||||||
ros::Publisher payload_pub;
|
ros::Publisher payload_pub;
|
||||||
ros::Publisher neigh_pos_pub;
|
ros::Publisher neigh_pos_pub;
|
||||||
|
@ -25,6 +25,7 @@ static char* dbgf_name;
|
|||||||
static const char* bzz_file;
|
static const char* bzz_file;
|
||||||
static int neigh=-1;
|
static int neigh=-1;
|
||||||
static int updater_msg_ready ;
|
static int updater_msg_ready ;
|
||||||
|
static int updated=0;
|
||||||
void init_update_monitor(const char* bo_filename, const char* stand_by_script,int barrier){
|
void init_update_monitor(const char* bo_filename, const char* stand_by_script,int barrier){
|
||||||
fprintf(stdout,"intiialized file monitor.\n");
|
fprintf(stdout,"intiialized file monitor.\n");
|
||||||
fd=inotify_init1(IN_NONBLOCK);
|
fd=inotify_init1(IN_NONBLOCK);
|
||||||
@ -280,7 +281,9 @@ buzzvm_pushs(VM, buzzvm_string_register(VM, "update_no", 1));
|
|||||||
buzzvm_pushs(VM, buzzvm_string_register(VM, "update_no", 1));
|
buzzvm_pushs(VM, buzzvm_string_register(VM, "update_no", 1));
|
||||||
buzzvm_pushi(VM, *(uint16_t*)(updater->update_no));
|
buzzvm_pushi(VM, *(uint16_t*)(updater->update_no));
|
||||||
buzzvm_gstore(VM);
|
buzzvm_gstore(VM);
|
||||||
neigh=0;
|
neigh=-1;
|
||||||
|
fprintf(stdout,"Sending code... \n");
|
||||||
|
code_message_outqueue_append();
|
||||||
}
|
}
|
||||||
delete_p(BO_BUF);
|
delete_p(BO_BUF);
|
||||||
}
|
}
|
||||||
@ -304,7 +307,8 @@ buzzvm_pushs(VM, buzzvm_string_register(VM, "update_no", 1));
|
|||||||
neigh=-1;
|
neigh=-1;
|
||||||
//collect_data();
|
//collect_data();
|
||||||
buzz_utility::buzz_update_init_test((updater)->bcode, (char*)dbgfname, *(size_t*)(updater->bcode_size));
|
buzz_utility::buzz_update_init_test((updater)->bcode, (char*)dbgfname, *(size_t*)(updater->bcode_size));
|
||||||
//buzzvm_function_call(m_tBuzzVM, "updated", 0);
|
//buzzvm_function_call(m_tBuzzVM, "updated", 0);
|
||||||
|
updated=1;
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
@ -393,7 +397,12 @@ delete_p(updater->outmsg_queue->size);
|
|||||||
delete_p(updater->outmsg_queue);
|
delete_p(updater->outmsg_queue);
|
||||||
updater_msg_ready=0;
|
updater_msg_ready=0;
|
||||||
}
|
}
|
||||||
|
int get_update_status(){
|
||||||
|
return updated;
|
||||||
|
}
|
||||||
|
void set_read_update_status(){
|
||||||
|
updated=0;
|
||||||
|
}
|
||||||
int get_update_mode(){
|
int get_update_mode(){
|
||||||
return (int)*(int*)(updater->mode);
|
return (int)*(int*)(updater->mode);
|
||||||
}
|
}
|
||||||
|
@ -133,7 +133,7 @@ namespace rosbzz_node{
|
|||||||
neigh_pos_pub = n_c.advertise<rosbuzz::neigh_pos>("/neighbours_pos",1000);
|
neigh_pos_pub = n_c.advertise<rosbuzz::neigh_pos>("/neighbours_pos",1000);
|
||||||
/* Clients*/
|
/* Clients*/
|
||||||
mav_client = n_c.serviceClient<mavros_msgs::CommandInt>(fcclient_name);
|
mav_client = n_c.serviceClient<mavros_msgs::CommandInt>(fcclient_name);
|
||||||
|
multi_msg=true;
|
||||||
}
|
}
|
||||||
|
|
||||||
void roscontroller::Compile_bzz(){
|
void roscontroller::Compile_bzz(){
|
||||||
@ -225,7 +225,7 @@ namespace rosbzz_node{
|
|||||||
delete[] payload_out_ptr;
|
delete[] payload_out_ptr;
|
||||||
|
|
||||||
|
|
||||||
if((int)get_update_mode()!=CODE_RUNNING && is_msg_present()==1){
|
if((int)get_update_mode()!=CODE_RUNNING && is_msg_present()==1 && multi_msg){
|
||||||
uint8_t* buff_send = 0;
|
uint8_t* buff_send = 0;
|
||||||
uint16_t updater_msgSize=*(uint16_t*) (getupdate_out_msg_size());;
|
uint16_t updater_msgSize=*(uint16_t*) (getupdate_out_msg_size());;
|
||||||
int tot=0;
|
int tot=0;
|
||||||
@ -254,8 +254,18 @@ namespace rosbzz_node{
|
|||||||
update_packets.payload64.push_back(payload_64[i]);
|
update_packets.payload64.push_back(payload_64[i]);
|
||||||
}
|
}
|
||||||
payload_pub.publish(update_packets);
|
payload_pub.publish(update_packets);
|
||||||
|
multi_msg=false;
|
||||||
delete[] payload_64;
|
delete[] payload_64;
|
||||||
}
|
}
|
||||||
|
/*Request xbee to stop any multi transmission updated not needed any more*/
|
||||||
|
if(get_update_status()){
|
||||||
|
set_read_update_status();
|
||||||
|
mavros_msgs::Mavlink stop_req_packet;
|
||||||
|
stop_req_packet.payload64.push_back((uint64_t) XBEE_STOP_TRANSMISSION);
|
||||||
|
payload_pub.publish(stop_req_packet);
|
||||||
|
std::cout << "request xbee to stop multi-packet transmission" << std::endl;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -445,8 +455,14 @@ namespace rosbzz_node{
|
|||||||
/*******************************************************************************************************/
|
/*******************************************************************************************************/
|
||||||
|
|
||||||
void roscontroller::payload_obt(const mavros_msgs::Mavlink::ConstPtr& msg){
|
void roscontroller::payload_obt(const mavros_msgs::Mavlink::ConstPtr& msg){
|
||||||
|
|
||||||
|
/*Ack from xbee about its transfer complete of multi packet*/
|
||||||
|
if((uint64_t)msg->payload64[0]==(uint64_t)XBEE_MESSAGE_CONSTANT && msg->payload64.size() == 1){
|
||||||
|
multi_msg=true;
|
||||||
|
std::cout << "ACK From xbee after transimssion of code " << std::endl;
|
||||||
|
}
|
||||||
|
|
||||||
if((uint64_t)msg->payload64[0]==(uint64_t)UPDATER_MESSAGE_CONSTANT){
|
else if((uint64_t)msg->payload64[0]==(uint64_t)UPDATER_MESSAGE_CONSTANT && msg->payload64.size() > 10){
|
||||||
uint16_t obt_msg_size=sizeof(uint64_t)*(msg->payload64.size());
|
uint16_t obt_msg_size=sizeof(uint64_t)*(msg->payload64.size());
|
||||||
uint64_t message_obt[obt_msg_size];
|
uint64_t message_obt[obt_msg_size];
|
||||||
/* Go throught the obtained payload*/
|
/* Go throught the obtained payload*/
|
||||||
|
Loading…
Reference in New Issue
Block a user