From 854edc36974d8c434de4d659a919969dfdd2f0a8 Mon Sep 17 00:00:00 2001 From: vivek-shankar Date: Sun, 2 Apr 2017 23:11:19 -0400 Subject: [PATCH] robots var --- src/roscontroller.cpp | 15 ++++++++------- 1 file changed, 8 insertions(+), 7 deletions(-) diff --git a/src/roscontroller.cpp b/src/roscontroller.cpp index 5012e47..1546527 100644 --- a/src/roscontroller.cpp +++ b/src/roscontroller.cpp @@ -73,8 +73,8 @@ namespace rosbzz_node{ multi_msg=true; } /*Set ROBOTS variable for barrier in .bzz from neighbours count*/ - no_of_robots=get_number_of_robots(); - //if(neighbours_pos_map.size() >0) no_of_robots =neighbours_pos_map.size()+1; + //no_of_robots=get_number_of_robots(); + if(neighbours_pos_map.size() >0) no_of_robots =neighbours_pos_map.size()+1; buzz_utility::set_robot_var(no_of_robots); /*Set no of robots for updates*/ updates_set_robots(no_of_robots); @@ -656,8 +656,9 @@ namespace rosbzz_node{ }*/ int roscontroller::get_number_of_robots(){ - if(count_robots.current !=0){ - uint8_t current_count,odd_count,odd_val=0; + //if(count_robots.current !=0){ + /* std::map< int, int> count_count; + uint8_t index=0; count_robots.history[count_robots.index]=neighbours_pos_map.size()+1; //count_robots.current=neighbours_pos_map.size()+1; count_robots.index++; @@ -676,8 +677,8 @@ namespace rosbzz_node{ if(odd_count>current_count){ count_robots.current=odd_val; } - } - else{ + //} + /*else{ if(neighbours_pos_map.size()!=0){ count_robots.history[count_robots.index]=neighbours_pos_map.size()+1; //count_robots.current=neighbours_pos_map.size()+1; @@ -687,7 +688,7 @@ namespace rosbzz_node{ count_robots.current=neighbours_pos_map.size()+1; } } - } + }*/ return count_robots.current; }