Skip to content
Open
Show file tree
Hide file tree
Changes from 1 commit
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
Prev Previous commit
Next Next commit
Builds with OpenCV4
  • Loading branch information
Kevin Michael Frick authored and rikba committed Oct 11, 2021
commit 46e55efb91d93f56bcf94e1b89a141d0330e884a
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,6 @@
#include <iostream>

#include <boost/filesystem.hpp>
#include <cv.h>
#include <highgui.h>
#include <opencv2/opencv.hpp>

#include "rotors_gazebo_plugins/common.h"
Expand Down Expand Up @@ -140,7 +138,7 @@ void GeotaggedImagesPlugin::OnNewFrame(const unsigned char * image)
Mat frame = Mat(height_, width_, CV_8UC3);
Mat frameBGR = Mat(height_, width_, CV_8UC3);
frame.data = (uchar*)image; //frame has not the right color format yet -> convert
cvtColor(frame, frameBGR, CV_RGB2BGR);
cvtColor(frame, frameBGR, cv::COLOR_RGB2BGR);

char file_name[256];
snprintf(file_name, sizeof(file_name), "%s/DSC%05i.jpg", storageDir_.c_str(), imageCounter_);
Expand Down
2 changes: 1 addition & 1 deletion rotors_gazebo_plugins/src/gazebo_odometry_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -89,7 +89,7 @@ void GazeboOdometryPlugin::Load(physics::ModelPtr _model,
if (_sdf->HasElement("covarianceImage")) {
std::string image_name =
_sdf->GetElement("covarianceImage")->Get<std::string>();
covariance_image_ = cv::imread(image_name, CV_LOAD_IMAGE_GRAYSCALE);
covariance_image_ = cv::imread(image_name, cv::IMREAD_GRAYSCALE);
if (covariance_image_.data == NULL)
gzerr << "loading covariance image " << image_name << " failed"
<< std::endl;
Expand Down