robot var fix

This commit is contained in:
vivek-shankar 2017-04-02 23:41:44 -04:00
parent 854edc3697
commit 6db4069f0d
2 changed files with 30 additions and 5 deletions

View File

@ -68,6 +68,9 @@ private:
int barrier;
int message_number=0;
int no_of_robots=0;
/*tmp to be corrected*/
int no_cnt=0;
int old_val=0;
std::string bzzfile_name, fcclient_name, armclient, modeclient, rcservice_name,bcfname,dbgfname,out_payload,in_payload,stand_by,xbeesrv_name;
bool rcclient;
bool multi_msg;
@ -167,7 +170,7 @@ private:
/*Robot independent subscribers*/
void Subscribe(ros::NodeHandle n_c);
int get_number_of_robots();
void get_number_of_robots();
};
}

View File

@ -74,7 +74,8 @@ namespace rosbzz_node{
}
/*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;
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);
@ -655,9 +656,31 @@ namespace rosbzz_node{
}*/
int roscontroller::get_number_of_robots(){
void roscontroller::get_number_of_robots(){
if(no_of_robots==0){
no_of_robots=neighbours_pos_map.size()+1;
}
else{
if(no_of_robots!=neighbours_pos_map.size()+1 && no_cnt==0){
no_cnt++;
old_val=neighbours_pos_map.size()+1;
}
else if(old_val==neighbours_pos_map.size()+1){
no_cnt++;
if(no_cnt==3){
no_of_robots=neighbours_pos_map.size()+1;
no_cnt=0;
}
}
else{
no_cnt=0;
}
}
//if(count_robots.current !=0){
/* std::map< int, int> count_count;
/*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;
@ -689,7 +712,6 @@ namespace rosbzz_node{
}
}
}*/
return count_robots.current;
}
}