changes in updater

This commit is contained in:
vivek-shankar 2017-01-31 01:11:59 -05:00
parent db1fd60616
commit 6a4c579630
5 changed files with 22 additions and 13 deletions

View File

@ -108,6 +108,8 @@ void destroy_out_msg_queue();
/***************************************************/ /***************************************************/
int get_update_mode(); int get_update_mode();
buzz_updater_elem_t get_updater();
/***************************************************/ /***************************************************/
/*sets bzz file name*/ /*sets bzz file name*/
/***************************************************/ /***************************************************/

View File

@ -10,7 +10,7 @@
<!-- param name="in_payload" value="/rosbuzz_node1/outMavlink"--> <!-- param name="in_payload" value="/rosbuzz_node1/outMavlink"-->
<param name="out_payload" value="/outMavlink"/> <param name="out_payload" value="/outMavlink"/>
<param name="robot_id" value="1"/> <param name="robot_id" value="1"/>
<param name="No_of_Robots" value="2"/> <param name="No_of_Robots" value="1"/>
<param name="stand_by" value="/home/vivek/catkin_ws/src/rosbuzz/src/stand_by.bo"/> <param name="stand_by" value="/home/vivek/catkin_ws/src/rosbuzz/src/stand_by.bo"/>
</node> </node>
<!-- node name="rosbuzz_node1" pkg="rosbuzz" type="rosbuzz_node" respawn="false" output="screen" --> <!-- node name="rosbuzz_node1" pkg="rosbuzz" type="rosbuzz_node" respawn="false" output="screen" -->

View File

@ -15,7 +15,7 @@
//static struct timeval t1, t2; //static struct timeval t1, t2;
static int timer_steps=0; static int timer_steps=0;
//static clock_t end; //static clock_t end;
void collect_data(); //void collect_data();
/*Temp end */ /*Temp end */
static int fd,wd =0; static int fd,wd =0;
static int old_update =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); fprintf(stdout,"Barrier ..................... %i \n",tObj->i.value);
if(tObj->i.value==no_of_robot) { if(tObj->i.value==no_of_robot) {
*(int*)(updater->mode) = CODE_RUNNING; *(int*)(updater->mode) = CODE_RUNNING;
collect_data(); //collect_data();
timer_steps=0; timer_steps=0;
//neigh=-1; //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); //buzzvm_function_call(m_tBuzzVM, "updated", 0);
updated=1; updated=1;
} }
@ -413,6 +413,9 @@ return (int)*(int*)(updater->mode);
int is_msg_present(){ int is_msg_present(){
return updater_msg_ready; return updater_msg_ready;
} }
buzz_updater_elem_t get_updater(){
return updater;
}
void destroy_updater(){ void destroy_updater(){
delete_p(updater->bcode); delete_p(updater->bcode);
delete_p(updater->bcode_size); delete_p(updater->bcode_size);

View File

@ -1,6 +1,5 @@
#include "roscontroller.h" #include "roscontroller.h"
namespace rosbzz_node{ namespace rosbzz_node{
/***Constructor***/ /***Constructor***/
@ -74,6 +73,10 @@ namespace rosbzz_node{
update_routine(bcfname.c_str(), dbgfname.c_str()); update_routine(bcfname.c_str(), dbgfname.c_str());
/*Step buzz script */ /*Step buzz script */
//fprintf(stdout, "before code step\n"); //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(); buzz_utility::buzz_script_step();
/*Prepare messages and publish them in respective topic*/ /*Prepare messages and publish them in respective topic*/
//fprintf(stdout, "before publish msg\n"); //fprintf(stdout, "before publish msg\n");
@ -271,14 +274,14 @@ namespace rosbzz_node{
delete[] payload_64; delete[] payload_64;
} }
/*Request xbee to stop any multi transmission updated not needed any more*/ /*Request xbee to stop any multi transmission updated not needed any more*/
if(get_update_status()){ //if(get_update_status()){
set_read_update_status(); // set_read_update_status();
mavros_msgs::Mavlink stop_req_packet; // mavros_msgs::Mavlink stop_req_packet;
stop_req_packet.payload64.push_back((uint64_t) XBEE_STOP_TRANSMISSION); // stop_req_packet.payload64.push_back((uint64_t) XBEE_STOP_TRANSMISSION);
payload_pub.publish(stop_req_packet); // payload_pub.publish(stop_req_packet);
std::cout << "request xbee to stop multi-packet transmission" << std::endl; // std::cout << "request xbee to stop multi-packet transmission" << std::endl;
} //}
} }

View File

@ -1,7 +1,8 @@
# We need this for 2D vectors # We need this for 2D vectors
# Make sure you pass the correct include path to "bzzc -I <path1:path2> ..." # Make sure you pass the correct include path to "bzzc -I <path1:path2> ..."
include "/home/ubuntu/buzz/src/include/vec2.bzz" include "/home/vivek/catkin_ws/src/rosbuzz/src/vec2.bzz"
#################################################################################################### ####################################################################################################
# Updater related # Updater related
# This should be here for the updater to work, changing position of code will crash the updater # This should be here for the updater to work, changing position of code will crash the updater