ROBOTS variable adaptation for updates
This commit is contained in:
parent
0124083b25
commit
8218474082
|
@ -21,7 +21,7 @@ barrier_val = barrier.size()
|
|||
neighbors.listen(updated,
|
||||
function(vid, value, rid) {
|
||||
print(" got from",vid," ", " value = ",value," ","rid"," " )
|
||||
if(value==update_no) barrier_val=ROBOTS
|
||||
if(value==update_no) barrier.put(rid,1)
|
||||
}
|
||||
)
|
||||
|
||||
|
|
|
@ -122,6 +122,7 @@ namespace rosbzz_node{
|
|||
/*Set no of robots for updates TODO only when not updating*/
|
||||
if(multi_msg)
|
||||
updates_set_robots(no_of_robots);
|
||||
ROS_INFO("ROBOTS: %i , acutal : %i",(int)no_of_robots,(int)buzzdict_size(buzz_utility::get_vm()->swarmmembers)+1);
|
||||
/*run once*/
|
||||
ros::spinOnce();
|
||||
/*loop rate of ros*/
|
||||
|
@ -918,21 +919,21 @@ namespace rosbzz_node{
|
|||
|
||||
}*/
|
||||
void roscontroller::get_number_of_robots(){
|
||||
|
||||
int cur_robots=(int)buzzdict_size(buzz_utility::get_vm()->swarmmembers)+1;
|
||||
if(no_of_robots==0){
|
||||
no_of_robots=neighbours_pos_map.size()+1;
|
||||
no_of_robots=cur_robots;
|
||||
|
||||
}
|
||||
else{
|
||||
if(no_of_robots!=neighbours_pos_map.size()+1 && no_cnt==0){
|
||||
if(no_of_robots!=cur_robots && no_cnt==0){
|
||||
no_cnt++;
|
||||
old_val=neighbours_pos_map.size()+1;
|
||||
old_val=cur_robots;
|
||||
|
||||
}
|
||||
else if(no_cnt!=0 && old_val==neighbours_pos_map.size()+1){
|
||||
else if(no_cnt!=0 && old_val==cur_robots){
|
||||
no_cnt++;
|
||||
if(no_cnt>=40){
|
||||
no_of_robots=neighbours_pos_map.size()+1;
|
||||
if(no_cnt>=8){
|
||||
no_of_robots=cur_robots;
|
||||
no_cnt=0;
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue