Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Noetic Migration and Bugfixes for OpenCV AdaBoosting #17

Merged
merged 9 commits into from
Jan 11, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 4 additions & 0 deletions .travis.yml
Original file line number Diff line number Diff line change
Expand Up @@ -14,11 +14,15 @@ env:
- ROS_DISTRO=kinetic UPSTREAM_WORKSPACE=debian
- ROS_DISTRO=melodic UPSTREAM_WORKSPACE=file
- ROS_DISTRO=melodic UPSTREAM_WORKSPACE=debian
- ROS_DISTRO=noetic UPSTREAM_WORKSPACE=file
- ROS_DISTRO=noetic UPSTREAM_WORKSPACE=debian

matrix:
allow_failures:
- env: ROS_DISTRO=kinetic UPSTREAM_WORKSPACE=file
- env: ROS_DISTRO=kinetic UPSTREAM_WORKSPACE=debian
- env: ROS_DISTRO=melodic UPSTREAM_WORKSPACE=debian
- env: ROS_DISTRO=noetic UPSTREAM_WORKSPACE=debian
install:
- git clone https://github.com/ros-industrial/industrial_ci.git .ci_config
script:
Expand Down
29 changes: 24 additions & 5 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -3,12 +3,31 @@ Algorithms for floor plan segmentation and systematic coverage driving patterns

## ROS Distro Support

| | Indigo | Jade | Kinetic | Melodic |
|:-------:|:------:|:----:|:-------:|:-------:|
| Branch | [`indigo_dev`](https://github.com/ipa320/ipa_coverage_planning/tree/indigo_dev) | [`indigo_dev`](https://github.com/ipa320/ipa_coverage_planning/tree/indigo_dev) | [`indigo_dev`](https://github.com/ipa320/ipa_coverage_planning/tree/indigo_dev) | [`melodic_dev`](https://github.com/ipa320/ipa_coverage_planning/tree/melodic_dev) |
| Status | not supported | not supported | supported | supported |
| Version | [version](http://repositories.ros.org/status_page/ros_indigo_default.html?q=ipa_coverage_planning) | [version](http://repositories.ros.org/status_page/ros_jade_default.html?q=ipa_coverage_planning) | [version](http://repositories.ros.org/status_page/ros_kinetic_default.html?q=ipa_coverage_planning) | [version](http://repositories.ros.org/status_page/ros_melodic_default.html?q=ipa_coverage_planning)
| | Indigo | Jade | Kinetic | Melodic | Noetic |
|:-------:|:------:|:----:|:-------:|:-------:|:-------:|
| Branch | [`indigo_dev`](https://github.com/ipa320/ipa_coverage_planning/tree/indigo_dev) | [`indigo_dev`](https://github.com/ipa320/ipa_coverage_planning/tree/indigo_dev) | [`indigo_dev`](https://github.com/ipa320/ipa_coverage_planning/tree/indigo_dev) | [`melodic_dev`](https://github.com/ipa320/ipa_coverage_planning/tree/melodic_dev) |[`noetic_dev`](https://github.com/ipa320/ipa_coverage_planning/tree/noetic_dev) |
| Status | not supported | not supported | EOL | supported | supported |
| Version | [version](http://repositories.ros.org/status_page/ros_indigo_default.html?q=ipa_coverage_planning) | [version](http://repositories.ros.org/status_page/ros_jade_default.html?q=ipa_coverage_planning) | [version](http://repositories.ros.org/status_page/ros_kinetic_default.html?q=ipa_coverage_planning) | [version](http://repositories.ros.org/status_page/ros_melodic_default.html?q=ipa_coverage_planning) | [version](http://repositories.ros.org/status_page/ros_noetic_default.html?q=ipa_coverage_planning)

## Travis - Continuous Integration

Status: [![Build Status](https://travis-ci.org/ipa320/ipa_coverage_planning.svg?branch=indigo_dev)](https://travis-ci.org/ipa320/ipa_coverage_planning)


## Quick start

1. Bring up your robot or launch the turtlebot3 simulation

1. Start the room exploration action server:

```
roslaunch ipa_room_exploration room_exploration_action_server.launch
```


1. Start the room exploration action client:

```
roslaunch ipa_room_exploration room_exploration_client.launch robot_env:=your-robot-env use_test_maps:=false
```

Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,11 @@ cv::Point TrolleyPositionFinder::findOneTrolleyPosition(const std::vector<cv::Po
cv::Mat temporary_map = original_map.clone();
cv::erode(temporary_map, temporary_map, cv::Mat());
cv::Mat distance_map; //variable for the distance-transformed map, type: CV_32FC1
#if CV_MAJOR_VERSION<=3
cv::distanceTransform(temporary_map, distance_map, CV_DIST_L2, 5);
#else
cv::distanceTransform(temporary_map, distance_map, cv::DIST_L2, 5);
#endif
cv::convertScaleAbs(distance_map, distance_map); // conversion to 8 bit image

//
Expand Down
20 changes: 18 additions & 2 deletions ipa_building_navigation/ros/src/boosttest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -112,24 +112,40 @@ int main(int argc, char **argv)

//create maps to draw the paths in
cv::Mat nearest_map = map.clone();
#if CV_MAJOR_VERSION<=3
cv::cvtColor(nearest_map, nearest_map, CV_GRAY2BGR);
#else
cv::cvtColor(nearest_map, nearest_map, cv::COLOR_GRAY2BGR);
#endif
cv::Mat genetic_map = nearest_map.clone();
cv::Mat concorde_map = nearest_map.clone();

//draw the order into the maps
// draw the start node as red
std::cout << "starting to draw the maps" << std::endl;
#if CV_MAJOR_VERSION<=3
cv::circle(nearest_map, nodes[nearest_order[0]], 2, CV_RGB(255,0,0), CV_FILLED);
cv::circle(genetic_map, nodes[genetic_order[0]], 2, CV_RGB(255,0,0), CV_FILLED);
cv::circle(concorde_map, nodes[concorde_order[0]], 2, CV_RGB(255,0,0), CV_FILLED);
#else
cv::circle(nearest_map, nodes[nearest_order[0]], 2, CV_RGB(255,0,0), cv::FILLED);
cv::circle(genetic_map, nodes[genetic_order[0]], 2, CV_RGB(255,0,0), cv::FILLED);
cv::circle(concorde_map, nodes[concorde_order[0]], 2, CV_RGB(255,0,0), cv::FILLED);
#endif
for(size_t i = 1; i < nearest_order.size(); ++i)
{
cv::line(nearest_map, nodes[nearest_order[i-1]], nodes[nearest_order[i]], CV_RGB(128,128,255), 1);
cv::circle(nearest_map, nodes[nearest_order[i]], 2, CV_RGB(0,0,0), CV_FILLED);
cv::line(genetic_map, nodes[genetic_order[i-1]], nodes[genetic_order[i]], CV_RGB(128,128,255), 1);
cv::circle(genetic_map, nodes[genetic_order[i]], 2, CV_RGB(0,0,0), CV_FILLED);
cv::line(concorde_map, nodes[concorde_order[i-1]], nodes[concorde_order[i]], CV_RGB(128,128,255), 1);
#if CV_MAJOR_VERSION<=3
cv::circle(nearest_map, nodes[nearest_order[i]], 2, CV_RGB(0,0,0), CV_FILLED);
cv::circle(genetic_map, nodes[genetic_order[i]], 2, CV_RGB(0,0,0), CV_FILLED);
cv::circle(concorde_map, nodes[concorde_order[i]], 2, CV_RGB(0,0,0), CV_FILLED);
#else
cv::circle(nearest_map, nodes[nearest_order[i]], 2, CV_RGB(0,0,0), cv::FILLED);
cv::circle(genetic_map, nodes[genetic_order[i]], 2, CV_RGB(0,0,0), cv::FILLED);
cv::circle(concorde_map, nodes[concorde_order[i]], 2, CV_RGB(0,0,0), cv::FILLED);
#endif
}
//draw line back to start
cv::line(nearest_map, nodes[nearest_order[0]], nodes[nearest_order.back()], CV_RGB(128,128,255), 1);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -350,18 +350,30 @@ void RoomSequencePlanningServer::findRoomSequenceWithCheckpointsServer(const ipa
// trolley positions + connections
if (t>0)
{
#if CV_MAJOR_VERSION<=3
cv::circle(display, trolley_positions[t], 5, CV_RGB(0,0,255), CV_FILLED);
#else
cv::circle(display, trolley_positions[t], 5, CV_RGB(0,0,255), cv::FILLED);
#endif
cv::line(display, trolley_positions[t], trolley_positions[t-1], CV_RGB(128,128,255), 1);
}
else
{
#if CV_MAJOR_VERSION<=3
cv::circle(display, trolley_positions[t], 5, CV_RGB(255,0,0), CV_FILLED);
#else
cv::circle(display, trolley_positions[t], 5, CV_RGB(255,0,0), cv::FILLED);
#endif
}

// room positions and connections
for (size_t r=0; r<cliques[t].size(); ++r)
{
#if CV_MAJOR_VERSION<=3
cv::circle(display, room_cliques_as_points[t][r], 3, CV_RGB(0,255,0), CV_FILLED);
#else
cv::circle(display, room_cliques_as_points[t][r], 3, CV_RGB(0,255,0), cv::FILLED);
#endif
if (r==0)
cv::line(display, trolley_positions[t], room_cliques_as_points[t][r], CV_RGB(255,0,0), 1);
else
Expand Down Expand Up @@ -503,18 +515,30 @@ void RoomSequencePlanningServer::findRoomSequenceWithCheckpointsServer(const ipa
//std::cout << "starting to draw one clique. Position: " << trolley_positions[ot] << std::endl;
if (t>0)
{
#if CV_MAJOR_VERSION<=3
cv::circle(display, trolley_positions[ot], 5, CV_RGB(0,0,255), CV_FILLED);
#else
cv::circle(display, trolley_positions[ot], 5, CV_RGB(0,0,255), cv::FILLED);
#endif
cv::line(display, trolley_positions[ot], trolley_positions[optimal_trolley_sequence[t-1]], CV_RGB(128,128,255), 1);
}
else
{
#if CV_MAJOR_VERSION<=3
cv::circle(display, trolley_positions[ot], 5, CV_RGB(255,0,0), CV_FILLED);
#else
cv::circle(display, trolley_positions[ot], 5, CV_RGB(255,0,0), cv::FILLED);
#endif
}

// room positions and connections
for (size_t r=0; r<optimal_room_sequences[ot].size(); ++r)
{
#if CV_MAJOR_VERSION<=3
cv::circle(display, room_cliques_as_points[ot][optimal_room_sequences[ot][r]], 3, CV_RGB(0,255,0), CV_FILLED);
#else
cv::circle(display, room_cliques_as_points[ot][optimal_room_sequences[ot][r]], 3, CV_RGB(0,255,0), cv::FILLED);
#endif
if (r==0)
cv::line(display, trolley_positions[ot], room_cliques_as_points[ot][optimal_room_sequences[ot][r]], CV_RGB(255,0,0), 1);
else
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -1005,7 +1005,11 @@ class Evaluation
for(size_t i = 0; i < result_seg->room_information_in_pixel.size(); ++i)
{
cv::Point current_center (result_seg->room_information_in_pixel[i].room_center.x, result_seg->room_information_in_pixel[i].room_center.y);
#if CV_MAJOR_VERSION<=3
cv::circle(colour_segmented_map, current_center, 2, CV_RGB(0,0,255), CV_FILLED);
#else
cv::circle(colour_segmented_map, current_center, 2, CV_RGB(0,0,255), cv::FILLED);
#endif
}
// color image in unique colour to show the segmentation
if (cv::imwrite(segmented_map_filename.c_str(), colour_segmented_map) == false)
Expand All @@ -1017,7 +1021,11 @@ class Evaluation
cv::Mat sequence_map = cv_ptr_seq->image;
// draw in trash bins
for (size_t i=0; i<evaluation_data.trash_bin_locations_.size(); ++i)
#if CV_MAJOR_VERSION<=3
cv::circle(sequence_map, evaluation_data.trash_bin_locations_[i], 2, CV_RGB(128,0,255), CV_FILLED);
#else
cv::circle(sequence_map, evaluation_data.trash_bin_locations_[i], 2, CV_RGB(128,0,255), cv::FILLED);
#endif
if (cv::imwrite(sequence_map_filename.c_str(), sequence_map) == false)
ROS_ERROR("Error on writing file '%s'", sequence_map_filename.c_str());
std::string sequence_detail_map_filename = lower_path + evaluation_data.map_name_ + "_sequence_detail.png";
Expand Down Expand Up @@ -1396,7 +1404,11 @@ class Evaluation
for(size_t i = 0; i < result_seg->room_information_in_pixel.size(); ++i)
{
cv::Point current_center (result_seg->room_information_in_pixel[i].room_center.x, result_seg->room_information_in_pixel[i].room_center.y);
#if CV_MAJOR_VERSION<=3
cv::circle(colour_segmented_map, current_center, 2, CV_RGB(0,0,255), CV_FILLED);
#else
cv::circle(colour_segmented_map, current_center, 2, CV_RGB(0,0,255), cv::FILLED);
#endif
}
// color image in unique colour to show the segmentation
if (cv::imwrite(segmented_map_filename.c_str(), colour_segmented_map) == false)
Expand All @@ -1408,7 +1420,11 @@ class Evaluation
cv::Mat sequence_map = cv_ptr_seq->image;
// draw in trash bins
for (size_t i=0; i<evaluation_data.trash_bin_locations_.size(); ++i)
#if CV_MAJOR_VERSION<=3
cv::circle(sequence_map, evaluation_data.trash_bin_locations_[i], 2, CV_RGB(128,0,255), CV_FILLED);
#else
cv::circle(sequence_map, evaluation_data.trash_bin_locations_[i], 2, CV_RGB(128,0,255), cv::FILLED);
#endif
if (cv::imwrite(sequence_map_filename.c_str(), sequence_map) == false)
ROS_ERROR("Error on writing file '%s'", sequence_map_filename.c_str());
std::string sequence_detail_map_filename = lower_path + evaluation_data.map_name_ + "_sequence_detail.png";
Expand Down Expand Up @@ -1795,7 +1811,11 @@ class Evaluation
for(size_t i = 0; i < result_seg->room_information_in_pixel.size(); ++i)
{
cv::Point current_center (result_seg->room_information_in_pixel[i].room_center.x, result_seg->room_information_in_pixel[i].room_center.y);
#if CV_MAJOR_VERSION<=3
cv::circle(colour_segmented_map, current_center, 2, CV_RGB(0,0,255), CV_FILLED);
#else
cv::circle(colour_segmented_map, current_center, 2, CV_RGB(0,0,255), cv::FILLED);
#endif
}
// color image in unique colour to show the segmentation
if (cv::imwrite(segmented_map_filename.c_str(), colour_segmented_map) == false)
Expand All @@ -1807,7 +1827,11 @@ class Evaluation
cv::Mat sequence_map = cv_ptr_seq->image;
// draw in trash bins
for (size_t i=0; i<evaluation_data.trash_bin_locations_.size(); ++i)
#if CV_MAJOR_VERSION<=3
cv::circle(sequence_map, evaluation_data.trash_bin_locations_[i], 2, CV_RGB(128,0,255), CV_FILLED);
#else
cv::circle(sequence_map, evaluation_data.trash_bin_locations_[i], 2, CV_RGB(128,0,255), cv::FILLED);
#endif
if (cv::imwrite(sequence_map_filename.c_str(), sequence_map) == false)
ROS_ERROR("Error on writing file '%s'", sequence_map_filename.c_str());
std::string sequence_detail_map_filename = lower_path + evaluation_data.map_name_ + "_sequence_detail.png";
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -137,10 +137,18 @@ class GeneralizedPolygon
// compute visible center
MeanShift2D ms;
cv::Mat room = cv::Mat::zeros(max_y_+10, max_x_+10, CV_8UC1);
#if CV_MAJOR_VERSION<=3
cv::drawContours(room, std::vector<std::vector<cv::Point> >(1,vertices), -1, cv::Scalar(255), CV_FILLED);
#else
cv::drawContours(room, std::vector<std::vector<cv::Point> >(1,vertices), -1, cv::Scalar(255), cv::FILLED);
#endif
area_ = cv::countNonZero(room);
cv::Mat distance_map; //variable for the distance-transformed map, type: CV_32FC1
#if CV_MAJOR_VERSION<=3
cv::distanceTransform(room, distance_map, CV_DIST_L2, 5);
#else
cv::distanceTransform(room, distance_map, cv::DIST_L2, 5);
#endif
// find point set with largest distance to obstacles
double min_val = 0., max_val = 0.;
cv::minMaxLoc(distance_map, &min_val, &max_val);
Expand Down Expand Up @@ -180,7 +188,11 @@ class GeneralizedPolygon
{
// draw polygon in an black image with necessary size
cv::Mat black_image = cv::Mat(max_y_+10, max_x_+10, CV_8UC1, cv::Scalar(0));
#if CV_MAJOR_VERSION<=3
cv::drawContours(black_image, std::vector<std::vector<cv::Point> >(1,vertices_), -1, color, CV_FILLED);
#else
cv::drawContours(black_image, std::vector<std::vector<cv::Point> >(1,vertices_), -1, color, cv::FILLED);
#endif

// assign drawn map
image = black_image.clone();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -197,7 +197,11 @@ class GridGenerator
// use distance transform to find the pixels with maximum distance to obstacles, take from the maximum distance pixels the one
// closest to the original cell center
cv::Mat distances;
#if CV_MAJOR_VERSION<=3
cv::distanceTransform(cell_pixels, distances, CV_DIST_L2, 5);
#else
cv::distanceTransform(cell_pixels, distances, cv::DIST_L2, 5);
#endif
double max_distance = 0.;
cv::minMaxLoc(distances, 0, &max_distance, 0, &cell_center);
cell_center.x += x-half_cell_size;
Expand Down
4 changes: 4 additions & 0 deletions ipa_room_exploration/common/src/boustrophedon_explorator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -451,7 +451,11 @@ void BoustrophedonExplorer::computeCellDecomposition(const cv::Mat& room_map, co
{
cv::Mat cell_copy(cell_map_labels == i);
std::vector<std::vector<cv::Point> > cellsi;
#if CV_MAJOR_VERSION<=3
cv::findContours(cell_copy, cellsi, CV_RETR_EXTERNAL, CV_CHAIN_APPROX_SIMPLE);
#else
cv::findContours(cell_copy, cellsi, cv::RETR_EXTERNAL, cv::CHAIN_APPROX_SIMPLE);
#endif
cells.insert(cells.end(), cellsi.begin(), cellsi.end());
}

Expand Down
4 changes: 4 additions & 0 deletions ipa_room_exploration/common/src/neural_network_explorator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -309,7 +309,11 @@ void NeuralNetworkExplorator::getExplorationPath(const cv::Mat& room_map, std::v
// printing of the path computation
if(show_path_computation == true)
{
#if CV_MAJOR_VERSION<=3
cv::circle(black_map, next_neuron->getPosition(), 2, cv::Scalar((visited_neurons*5)%250), CV_FILLED);
#else
cv::circle(black_map, next_neuron->getPosition(), 2, cv::Scalar((visited_neurons*5)%250), cv::FILLED);
#endif
cv::line(black_map, previous_neuron->getPosition(), next_neuron->getPosition(), cv::Scalar(128), 1);
cv::imshow("next_neuron", black_map);
cv::waitKey();
Expand Down
4 changes: 4 additions & 0 deletions ipa_room_exploration/common/src/room_rotator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,11 @@ void RoomRotator::rotateRoom(const cv::Mat& room_map, cv::Mat& rotated_room_map,

// apply a binary filter to create a binary image, also use a closing operator to smooth the output (the rotation might produce
// black pixels reaching into the white area that were not there before, causing new, wrong cells to open)
#if CV_MAJOR_VERSION<=3
cv::threshold(rotated_room_map, rotated_room_map, 127, 255, CV_THRESH_BINARY);
#else
cv::threshold(rotated_room_map, rotated_room_map, 127, 255, cv::THRESH_BINARY);
#endif
// this should not be used because it removes smaller obstacles like thin walls from the room and hence lets a planner generate paths through walls
// cv::dilate(rotated_room_map, rotated_room_map, cv::Mat(), cv::Point(-1,-1), 1);
// cv::erode(rotated_room_map, rotated_room_map, cv::Mat(), cv::Point(-1,-1), 1);
Expand Down
4 changes: 4 additions & 0 deletions ipa_room_exploration/ros/src/coverage_check_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -131,7 +131,11 @@ void CoverageCheckServer::drawCoveredPointsPolygon(cv::Mat& reachable_areas_map,
// draw current field of view in map
cv::Mat fov_mat = cv::Mat::zeros(reachable_areas_map.rows, reachable_areas_map.cols, reachable_areas_map.type());
std::vector<std::vector<cv::Point> > contours(1, transformed_fov_points);
#if CV_MAJOR_VERSION<=3
cv::drawContours(fov_mat, contours, 0, cv::Scalar(255), CV_FILLED);
#else
cv::drawContours(fov_mat, contours, 0, cv::Scalar(255), cv::FILLED);
#endif

// check visibility for each pixel of the fov area
for (int v=0; v<fov_mat.rows; ++v)
Expand Down
4 changes: 4 additions & 0 deletions ipa_room_exploration/ros/src/fov_to_robot_mapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -310,7 +310,11 @@ void computeFOVCenterAndRadius(const std::vector<Eigen::Matrix<float, 2, 1> >& f
}
cv::fillPoly(fov_image, polygon_array, cv::Scalar(255));
cv::Mat fov_distance_transform;
#if CV_MAJOR_VERSION<=3
cv::distanceTransform(fov_image, fov_distance_transform, CV_DIST_L2, CV_DIST_MASK_PRECISE);
#else
cv::distanceTransform(fov_image, fov_distance_transform, cv::DIST_L2, cv::DIST_MASK_PRECISE);
#endif

// determine the point(s) with maximum distance to the rim of the field of view, if multiple points apply, take the one closest to the center
float max_dist_val = 0.;
Expand Down
20 changes: 20 additions & 0 deletions ipa_room_exploration/ros/src/room_exploration_action_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -553,17 +553,29 @@ void RoomExplorationServer::exploreRoom(const ipa_building_msgs::RoomExploration
fov_path_map = room_map.clone();
cv::resize(fov_path_map, fov_path_map, cv::Size(), 2, 2, cv::INTER_LINEAR);
if (exploration_path.size() > 0)
#if CV_MAJOR_VERSION<=3
cv::circle(fov_path_map, 2*cv::Point((exploration_path[0].x-map_origin.x)/map_resolution, (exploration_path[0].y-map_origin.y)/map_resolution), 2, cv::Scalar(150), CV_FILLED);
#else
cv::circle(fov_path_map, 2*cv::Point((exploration_path[0].x-map_origin.x)/map_resolution, (exploration_path[0].y-map_origin.y)/map_resolution), 2, cv::Scalar(150), cv::FILLED);
#endif
for(size_t i=1; i<=step; ++i)
{
cv::Point p1((exploration_path[i-1].x-map_origin.x)/map_resolution, (exploration_path[i-1].y-map_origin.y)/map_resolution);
cv::Point p2((exploration_path[i].x-map_origin.x)/map_resolution, (exploration_path[i].y-map_origin.y)/map_resolution);
#if CV_MAJOR_VERSION<=3
cv::circle(fov_path_map, 2*p2, 2, cv::Scalar(200), CV_FILLED);
#else
cv::circle(fov_path_map, 2*p2, 2, cv::Scalar(200), cv::FILLED);
#endif
cv::line(fov_path_map, 2*p1, 2*p2, cv::Scalar(150), 1);
cv::Point p3(p2.x+5*cos(exploration_path[i].theta), p2.y+5*sin(exploration_path[i].theta));
if (i==step)
{
#if CV_MAJOR_VERSION<=3
cv::circle(fov_path_map, 2*p2, 2, cv::Scalar(80), CV_FILLED);
#else
cv::circle(fov_path_map, 2*p2, 2, cv::Scalar(80), cv::FILLED);
#endif
cv::line(fov_path_map, 2*p1, 2*p2, cv::Scalar(150), 1);
cv::line(fov_path_map, 2*p2, 2*p3, cv::Scalar(50), 1);
}
Expand Down Expand Up @@ -887,10 +899,18 @@ void RoomExplorationServer::navigateExplorationPath(const std::vector<geometry_m

// draw found regions s.t. they can be intersected later
cv::Mat black_map(costmap_as_mat.cols, costmap_as_mat.rows, costmap_as_mat.type(), cv::Scalar(0));
#if CV_MAJOR_VERSION<=3
cv::drawContours(black_map, areas_to_revisit, -1, cv::Scalar(255), CV_FILLED);
#else
cv::drawContours(black_map, areas_to_revisit, -1, cv::Scalar(255), cv::FILLED);
#endif
for(size_t contour = 0; contour < left_areas.size(); ++contour)
if(hierarchy[contour][3] != -1)
#if CV_MAJOR_VERSION<=3
cv::drawContours(black_map, left_areas, contour, cv::Scalar(0), CV_FILLED);
#else
cv::drawContours(black_map, left_areas, contour, cv::Scalar(0), cv::FILLED);
#endif

// 2. Intersect the left areas with respect to the calculated grid length.
geometry_msgs::Polygon min_max_coordinates; // = goal->room_min_max;
Expand Down
Loading