Skip to content

Commit

Permalink
Fixed color encoding for cv::imshow.
Browse files Browse the repository at this point in the history
  • Loading branch information
mbjelonic committed Nov 20, 2017
1 parent 9f02598 commit 87f86f7
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 2 deletions.
4 changes: 3 additions & 1 deletion darknet_ros/src/YoloObjectDetector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -288,7 +288,9 @@ void YoloObjectDetector::runYolo(cv::Mat &fullFrame, const std_msgs::Header& hea
}

if(viewImage_ && !darknetImageViewer_) {
cv::imshow(opencvWindow_, inputFrame);
cv::Mat showImage;
cv::cvtColor(inputFrame, showImage, cv::COLOR_RGB2BGR);
cv::imshow(opencvWindow_, showImage);
cv::waitKey(waitKeyDelay_);
}

Expand Down
2 changes: 1 addition & 1 deletion darknet_ros/test/ObjectDetection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -82,7 +82,7 @@ bool sendImageToYolo(ros::NodeHandle nh, std::string imageName) {
// Get test image
cv_bridge::CvImagePtr cv_ptr(new cv_bridge::CvImage);
cv_ptr->image = cv::imread(pathToTestImage, CV_LOAD_IMAGE_COLOR);
cv_ptr->encoding = sensor_msgs::image_encodings::BGR8;
cv_ptr->encoding = sensor_msgs::image_encodings::RGB8;
sensor_msgs::ImagePtr image = cv_ptr->toImageMsg();

// Generate goal.
Expand Down

0 comments on commit 87f86f7

Please sign in to comment.