neigh pos removed
This commit is contained in:
parent
e0f2ee92ec
commit
85325b3091
|
@ -37,7 +37,7 @@ namespace rosbzz_node{
|
||||||
{
|
{
|
||||||
/*Update neighbors position inside Buzz*/
|
/*Update neighbors position inside Buzz*/
|
||||||
buzz_utility::neighbour_pos_callback(neighbours_pos_map);
|
buzz_utility::neighbour_pos_callback(neighbours_pos_map);
|
||||||
|
/*
|
||||||
map< int, buzz_utility::Pos_struct >::iterator it;
|
map< int, buzz_utility::Pos_struct >::iterator it;
|
||||||
rosbuzz::neigh_pos neigh_pos_array; //neigh_pos_array.clear();
|
rosbuzz::neigh_pos neigh_pos_array; //neigh_pos_array.clear();
|
||||||
sensor_msgs::NavSatFix tmp;
|
sensor_msgs::NavSatFix tmp;
|
||||||
|
@ -48,7 +48,7 @@ namespace rosbzz_node{
|
||||||
tmp.altitude=(it->second).z;
|
tmp.altitude=(it->second).z;
|
||||||
neigh_pos_array.pos_neigh.push_back(tmp);
|
neigh_pos_array.pos_neigh.push_back(tmp);
|
||||||
}
|
}
|
||||||
neigh_pos_pub.publish(neigh_pos_array);
|
neigh_pos_pub.publish(neigh_pos_array); */
|
||||||
|
|
||||||
/*Check updater state and step code*/
|
/*Check updater state and step code*/
|
||||||
if(update_routine(bcfname.c_str(), dbgfname.c_str(),0)==CODE_RUNNING)
|
if(update_routine(bcfname.c_str(), dbgfname.c_str(),0)==CODE_RUNNING)
|
||||||
|
@ -207,7 +207,7 @@ namespace rosbzz_node{
|
||||||
void roscontroller::maintain_pos(int tim_step){
|
void roscontroller::maintain_pos(int tim_step){
|
||||||
if(timer_step >=10){
|
if(timer_step >=10){
|
||||||
neighbours_pos_map.clear();
|
neighbours_pos_map.clear();
|
||||||
raw_neighbours_pos_map.clear();
|
//raw_neighbours_pos_map.clear();
|
||||||
timer_step=0;
|
timer_step=0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -303,7 +303,7 @@ namespace rosbzz_node{
|
||||||
/*pass neighbour position to local maintaner*/
|
/*pass neighbour position to local maintaner*/
|
||||||
buzz_utility::Pos_struct n_pos(cvt_neighbours_pos_payload[0],cvt_neighbours_pos_payload[1],cvt_neighbours_pos_payload[2]);
|
buzz_utility::Pos_struct n_pos(cvt_neighbours_pos_payload[0],cvt_neighbours_pos_payload[1],cvt_neighbours_pos_payload[2]);
|
||||||
/*Put RID and pos*/
|
/*Put RID and pos*/
|
||||||
raw_neighbours_pos_put((int)out[1],n_pos);
|
//raw_neighbours_pos_put((int)out[1],n_pos);
|
||||||
neighbours_pos_put((int)out[1],n_pos);
|
neighbours_pos_put((int)out[1],n_pos);
|
||||||
delete[] out;
|
delete[] out;
|
||||||
buzz_utility::in_msg_process((message_obt+3));
|
buzz_utility::in_msg_process((message_obt+3));
|
||||||
|
|
Loading…
Reference in New Issue