robots var
This commit is contained in:
parent
4aa8e36eb3
commit
854edc3697
|
@ -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;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue