diff --git a/include/buzz_update.h b/include/buzz_update.h
index b88b8ea..34355f7 100644
--- a/include/buzz_update.h
+++ b/include/buzz_update.h
@@ -108,6 +108,8 @@ void destroy_out_msg_queue();
/***************************************************/
int get_update_mode();
+
+buzz_updater_elem_t get_updater();
/***************************************************/
/*sets bzz file name*/
/***************************************************/
diff --git a/launch/rosbuzz_2_parallel.launch b/launch/rosbuzz_2_parallel.launch
index cf507a1..44841ea 100644
--- a/launch/rosbuzz_2_parallel.launch
+++ b/launch/rosbuzz_2_parallel.launch
@@ -10,7 +10,7 @@
-
+
diff --git a/src/buzz_update.cpp b/src/buzz_update.cpp
index 9756b8f..6bdb8b7 100644
--- a/src/buzz_update.cpp
+++ b/src/buzz_update.cpp
@@ -15,7 +15,7 @@
//static struct timeval t1, t2;
static int timer_steps=0;
//static clock_t end;
-void collect_data();
+//void collect_data();
/*Temp end */
static int fd,wd =0;
static int old_update =0;
@@ -306,10 +306,10 @@ buzzvm_pushs(VM, buzzvm_string_register(VM, "update_no", 1));
fprintf(stdout,"Barrier ..................... %i \n",tObj->i.value);
if(tObj->i.value==no_of_robot) {
*(int*)(updater->mode) = CODE_RUNNING;
- collect_data();
+ //collect_data();
timer_steps=0;
//neigh=-1;
- buzz_utility::buzz_update_set((updater)->bcode, (char*)dbgfname, *(size_t*)(updater->bcode_size));
+ //buzz_utility::buzz_update_set((updater)->bcode, (char*)dbgfname, *(size_t*)(updater->bcode_size));
//buzzvm_function_call(m_tBuzzVM, "updated", 0);
updated=1;
}
@@ -413,6 +413,9 @@ return (int)*(int*)(updater->mode);
int is_msg_present(){
return updater_msg_ready;
}
+buzz_updater_elem_t get_updater(){
+return updater;
+}
void destroy_updater(){
delete_p(updater->bcode);
delete_p(updater->bcode_size);
diff --git a/src/roscontroller.cpp b/src/roscontroller.cpp
index 0b63b2a..c6fc378 100644
--- a/src/roscontroller.cpp
+++ b/src/roscontroller.cpp
@@ -1,6 +1,5 @@
#include "roscontroller.h"
-
namespace rosbzz_node{
/***Constructor***/
@@ -74,6 +73,10 @@ namespace rosbzz_node{
update_routine(bcfname.c_str(), dbgfname.c_str());
/*Step buzz script */
//fprintf(stdout, "before code step\n");
+ if(get_update_status()){
+ buzz_utility::buzz_update_set((get_updater())->bcode, dbgfname.c_str(), *(size_t*)((get_updater())->bcode_size));
+ set_read_update_status();;
+ }
buzz_utility::buzz_script_step();
/*Prepare messages and publish them in respective topic*/
//fprintf(stdout, "before publish msg\n");
@@ -271,14 +274,14 @@ namespace rosbzz_node{
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;
+ //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;
- }
+ //}
}
diff --git a/src/test1.bzz b/src/test1.bzz
index 993eca4..d50abd3 100644
--- a/src/test1.bzz
+++ b/src/test1.bzz
@@ -1,7 +1,8 @@
+
# We need this for 2D vectors
# Make sure you pass the correct include path to "bzzc -I ..."
-include "/home/ubuntu/buzz/src/include/vec2.bzz"
+include "/home/vivek/catkin_ws/src/rosbuzz/src/vec2.bzz"
####################################################################################################
# Updater related
# This should be here for the updater to work, changing position of code will crash the updater