Skip to content

Commit

Permalink
decreased frontier size
Browse files Browse the repository at this point in the history
  • Loading branch information
gajena committed Jul 30, 2018
1 parent 77ed1f3 commit c1e53e9
Show file tree
Hide file tree
Showing 2 changed files with 15 additions and 16 deletions.
29 changes: 14 additions & 15 deletions src/frontier_search.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -127,7 +127,7 @@ std::vector<std::vector<std::pair<int, int>>> FrontierSearch::buildBidimensional
//Remove small frontiers (single cell like). To improve: remove coherently with the robot size, based on the cell resolution of the map.
for (int i = 0; i < frontiers.size(); i++)
{
if (frontiers[i].size() < 15)
if (frontiers[i].size() < 5)
{
frontiers.erase(frontiers.begin() + i);
i--;
Expand Down Expand Up @@ -221,24 +221,23 @@ std::vector<std::pair<int, int>> FrontierSearch::getCentroids(std::vector<std::v
}
x_centroid /= frontier.size();
y_centroid /= frontier.size();
float dist = 1000000;
float x_temp = x_centroid;
float y_temp = y_centroid;
for (std::pair<int, int> cell : frontier)
{
float min_dist = sqrt(pow((x_temp - cell.first), 2) + pow((y_temp - cell.second), 2));
if (dist > min_dist)
{
dist = min_dist;
x_centroid = cell.first;
y_centroid = cell.second;
}
}
// float dist = 1000000;
//float x_temp = x_centroid;
/// float y_temp = y_centroid;
// for (std::pair<int, int> cell : frontier)
//{
// float min_dist = sqrt(pow((x_temp - cell.first), 2) + pow((y_temp - cell.second), 2));
// if (dist > min_dist)
// {
// dist = min_dist;
// x_centroid = cell.first;
// y_centroid = cell.second;
// }
//}
centroids.push_back(std::pair<int, int>(x_centroid, y_centroid));

float rwX = y_centroid * map_.info.resolution + map_.info.origin.position.x; //swapped because of a mess with the row major ordering......
float rwY = x_centroid * map_.info.resolution + map_.info.origin.position.y;

float distance = sqrt(pow(rwX - pose_x, 2) + pow(rwY - pose_y, 2));
if (distance < min_distance)
{
Expand Down
2 changes: 1 addition & 1 deletion src/robot_exploration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,7 @@ int main(int argc, char **argv)
}
}

frontier_pub.publish(robot_exploration.frontiers_map);
// frontier_pub.publish(robot_exploration.frontiers_map);
ros::spinOnce();

if(!robot_exploration.centroids.empty()){
Expand Down

0 comments on commit c1e53e9

Please sign in to comment.