Skip to content

Commit

Permalink
Update opencv to version 4 for noetic
Browse files Browse the repository at this point in the history
  • Loading branch information
geethikah21 committed Jul 4, 2024
1 parent 093beac commit 85004cc
Show file tree
Hide file tree
Showing 15 changed files with 25 additions and 25 deletions.
2 changes: 1 addition & 1 deletion bwi_mapper/include/bwi_mapper/connected_components.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@

#pragma once

#include <opencv/cv.h>
#include <opencv2/opencv.hpp>
#include <vector>

namespace bwi_mapper {
Expand Down
2 changes: 1 addition & 1 deletion bwi_mapper/include/bwi_mapper/graph.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@
#include <boost/graph/labeled_graph.hpp>
#include <bwi_mapper/structures/point.h>

#include <opencv/cv.h>
#include <opencv2/opencv.hpp>
#include <nav_msgs/MapMetaData.h>
#include <nav_msgs/OccupancyGrid.h>

Expand Down
2 changes: 1 addition & 1 deletion bwi_mapper/include/bwi_mapper/map_loader.h
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@
#include <nav_msgs/GetMap.h>
#include <nav_msgs/GetMapResponse.h>
#include <yaml-cpp/yaml.h>
#include <opencv/cv.h>
#include <opencv2/opencv.hpp>

namespace bwi_mapper {

Expand Down
2 changes: 1 addition & 1 deletion bwi_mapper/include/bwi_mapper/structures/point.h
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@

#pragma once

#include <opencv/cv.h>
#include <opencv2/opencv.hpp>
#include <stdint.h>

namespace bwi_mapper {
Expand Down
4 changes: 2 additions & 2 deletions bwi_mapper/src/libbwi_mapper/connected_components.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -62,12 +62,12 @@ namespace bwi_mapper {
std::vector<cv::Vec4i> hierarchy;

cv::findContours(src, contours, hierarchy,
CV_RETR_CCOMP, CV_CHAIN_APPROX_SIMPLE);
cv::RETR_CCOMP, cv::CHAIN_APPROX_SIMPLE);

number_components_ = 0;
for(int idx = 0; idx >= 0; idx = hierarchy[idx][0]) {
cv::Scalar color(number_components_ + 1);
cv::drawContours(dst, contours, idx, color, CV_FILLED, 8, hierarchy);
cv::drawContours(dst, contours, idx, color, cv::FILLED, 8, hierarchy);
number_components_++;
}

Expand Down
16 changes: 8 additions & 8 deletions bwi_mapper/src/libbwi_mapper/graph.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -105,7 +105,7 @@ namespace bwi_mapper {
cv::Point end_shift = end_pt + shift_ratio * (start_pt - end_pt);
cv::line(image, start_shift, end_shift,
cv::Scalar(160, 160, 255),
4, CV_AA); // draw an anti aliased line
4, cv::LINE_AA); // draw an anti aliased line
}
}
}
Expand All @@ -123,10 +123,10 @@ namespace bwi_mapper {
text_loc = text_loc + cv::Point(-7,0);
}
cv::putText(image, boost::lexical_cast<std::string>(count), text_loc,
cv::FONT_HERSHEY_SIMPLEX, 0.7, cvScalar(0,0,255), 2, CV_AA);
cv::FONT_HERSHEY_SIMPLEX, 0.7, cv::Scalar(0,0,255), 2, cv::LINE_AA);
} else {
size_t vertex_size = 13; // + graph[*vi].pixels / 10;
cv::circle(image, vertex_loc, vertex_size, cv::Scalar(0,0,255), -1, CV_AA);
cv::circle(image, vertex_loc, vertex_size, cv::Scalar(0,0,255), -1, cv::LINE_AA);
}
count++;
}
Expand All @@ -142,7 +142,7 @@ namespace bwi_mapper {
cv::Point2f(size * cosf(orientation + M_PI/2),
size * sinf(orientation + M_PI/2));

cv::line(image, arrow_start, arrow_end, color, thickness, CV_AA);
cv::line(image, arrow_start, arrow_end, color, thickness, cv::LINE_AA);

// http://mlikihazar.blogspot.com/2013/02/draw-arrow-opencv.html
cv::Point p(arrow_start), q(arrow_end);
Expand All @@ -151,12 +151,12 @@ namespace bwi_mapper {
float angle = atan2f(p.y - q.y, p.x - q.x);
p.x = (int) (q.x + (size/2 - 1) * cos(angle + M_PI/4));
p.y = (int) (q.y + (size/2 - 1) * sin(angle + M_PI/4));
cv::line(image, p, q, color, thickness, CV_AA);
cv::line(image, p, q, color, thickness, cv::LINE_AA);

//Draw the second segment
p.x = (int) (q.x + (size/2 + 1) * cos(angle - M_PI/4));
p.y = (int) (q.y + (size/2 + 1) * sin(angle - M_PI/4));
cv::line(image, p, q, color, thickness, CV_AA);
cv::line(image, p, q, color, thickness, cv::LINE_AA);

}

Expand Down Expand Up @@ -186,7 +186,7 @@ namespace bwi_mapper {
uint32_t orig_x, uint32_t orig_y) {
Point2f loc = getLocationFromGraphId(node, graph);
cv::Point circle_loc(loc.x + orig_x, loc.y + orig_y);
cv::circle(image, circle_loc, 15, color, 2, CV_AA);
cv::circle(image, circle_loc, 15, color, 2, cv::LINE_AA);
}

void drawSquareOnGraph(cv::Mat &image, const Graph& graph,
Expand All @@ -195,7 +195,7 @@ namespace bwi_mapper {
Point2f loc = getLocationFromGraphId(node, graph);
cv::Point square_loc(loc.x + orig_x, loc.y + orig_y);
cv::Rect rect(square_loc.x - size/2, square_loc.y - size/2, size, size);
cv::rectangle(image, rect, color, thickness, CV_AA);
cv::rectangle(image, rect, color, thickness, cv::LINE_AA);
}

void writeGraphToFile(const std::string &filename,
Expand Down
6 changes: 3 additions & 3 deletions bwi_mapper/src/libbwi_mapper/topological_mapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@

#include <boost/foreach.hpp>

#include <opencv/highgui.h>
#include <opencv2/highgui.hpp>
#include <opencv2/opencv_modules.hpp>
#ifdef HAVE_OPENCV_IMGCODECS
// this is OpenCV 3 and we need extra includes
Expand Down Expand Up @@ -329,7 +329,7 @@ namespace bwi_mapper {
// connected regions
cv::Mat component_map_color;
drawMap(component_map_color, inflated_map_);
cvtColor(component_map_color, component_image_, CV_RGB2GRAY);
cvtColor(component_map_color, component_image_, cv::COLOR_RGB2GRAY);
drawCriticalLines(component_image_);

component_map_.resize(
Expand Down Expand Up @@ -1041,7 +1041,7 @@ namespace bwi_mapper {
cv::Point(orig_x + p1.x, orig_y + p1.y),
cv::Point(orig_x + p2.x, orig_y + p2.y),
color,
2, CV_AA); // draw a 4 connected line
2, cv::LINE_AA); // draw a 4 connected line
}
}
}
Expand Down
2 changes: 1 addition & 1 deletion bwi_mapper/src/libbwi_mapper/voronoi_approximator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -239,7 +239,7 @@ namespace bwi_mapper {
for (size_t i = 0; i < voronoi_points_.size(); ++i) {
VoronoiPoint &vp = voronoi_points_[i];
cv::Point p(vp.x + orig_x, orig_y + vp.y);
cv::circle(image, p, 1, cv::Scalar(255,0,0), -1, CV_AA);
cv::circle(image, p, 1, cv::Scalar(255,0,0), -1, cv::LINE_AA);
// image.at<cv::Vec3b>
// (orig_y + vp.y, vp.x + orig_x) =
// cv::Vec3b(255,0,0);
Expand Down
2 changes: 1 addition & 1 deletion bwi_mapper/src/nodes/generate_graph.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ int main(int argc, char** argv) {
std::string filename(argv[2]);
mapper.writePointGraphToFile(filename);

cv::namedWindow("Display window", CV_WINDOW_AUTOSIZE);
cv::namedWindow("Display window", cv::WINDOW_AUTOSIZE);
cv::imshow("Display window", image);

cv::waitKey(0); // Wait for a keystroke in the window
Expand Down
2 changes: 1 addition & 1 deletion bwi_mapper/src/nodes/prepare_graph.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -142,7 +142,7 @@ int main(int argc, char** argv) {
mapper.drawMap(image);
drawElementsFile(argv[3], image, graph, info);

cv::namedWindow("Display window", CV_WINDOW_AUTOSIZE);
cv::namedWindow("Display window", cv::WINDOW_AUTOSIZE);
cv::imshow("Display window", image);
cv::imwrite("out.png", image);

Expand Down
2 changes: 1 addition & 1 deletion bwi_mapper/src/nodes/view_graph.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ int main(int argc, char** argv) {
mapper.drawMap(image);
bwi_mapper::drawGraph(image, graph);

cv::namedWindow("Display window", CV_WINDOW_NORMAL);
cv::namedWindow("Display window", cv::WINDOW_NORMAL);
cv::imshow("Display window", image);

cv::waitKey(0); // Wait for a keystroke in the window
Expand Down
2 changes: 1 addition & 1 deletion bwi_mapper/test/test_graph.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ int main(int argc, char** argv) {
mapper.drawOutput(image);
mapper.saveOutput();

cv::namedWindow("Display window", CV_WINDOW_AUTOSIZE);
cv::namedWindow("Display window", cv::WINDOW_AUTOSIZE);
cv::imshow("Display window", image);

cv::waitKey(0); // Wait for a keystroke in the window
Expand Down
2 changes: 1 addition & 1 deletion bwi_mapper/test/test_map_loader.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ int main(int argc, char** argv) {
cv::Mat image;
ml.drawMap(image, 10, 10);

cv::namedWindow("Display window", CV_WINDOW_AUTOSIZE);
cv::namedWindow("Display window", cv::WINDOW_AUTOSIZE);
cv::imshow("Display window", image);

cv::waitKey(0); // Wait for a keystroke in the window
Expand Down
2 changes: 1 addition & 1 deletion bwi_mapper/test/test_voronoi.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -90,7 +90,7 @@ int main(int argc, char** argv) {
voronoi4.drawVoronoiPoints(image);
cv::imwrite("voronoi_naive_4.png", image);

cv::namedWindow("Display window", CV_WINDOW_AUTOSIZE);
cv::namedWindow("Display window", cv::WINDOW_AUTOSIZE);
cv::imshow("Display window", display_image);

cv::waitKey(0); // Wait for a keystroke in the window
Expand Down
2 changes: 1 addition & 1 deletion bwi_tools/include/bwi_tools/point.h
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
#ifndef BWI_TOOLS_POINT_H
#define BWI_TOOLS_POINT_H

#include <opencv/cv.h>
#include <opencv2/opencv.hpp>

namespace bwi {

Expand Down

0 comments on commit 85004cc

Please sign in to comment.