Skip to content

Commit

Permalink
[adding_images] convert input image to bgr8 encoding and publish bgr8…
Browse files Browse the repository at this point in the history
… image
  • Loading branch information
iory committed Sep 1, 2016
1 parent 4ea3364 commit e81b9d1
Showing 1 changed file with 12 additions and 1 deletion.
13 changes: 12 additions & 1 deletion src/nodelet/adding_images_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -170,6 +170,16 @@ namespace adding_images {
cv::Mat image2 =
cv_bridge::toCvShare(image_msg2, image_msg2->encoding)->image;

// convert image to bgr8
if (image_msg1->encoding == sensor_msgs::image_encodings::RGB8 ||
image_msg1->encoding == sensor_msgs::image_encodings::RGB16) {
cv::cvtColor(image1, image1, CV_RGB2BGR);
}
if (image_msg2->encoding == sensor_msgs::image_encodings::RGB8 ||
image_msg2->encoding == sensor_msgs::image_encodings::RGB16) {
cv::cvtColor(image2, image2, CV_RGB2BGR);
}

cv::Mat result_image;
cv::addWeighted(image1, alpha_, image2, beta_, gamma_, result_image);
//-- Show what you got
Expand All @@ -178,8 +188,9 @@ namespace adding_images {
cv::imshow(window_name_, result_image);
int c = cv::waitKey(1);
}
// publish bgr8 image
img_pub_.publish(cv_bridge::CvImage(image_msg1->header,
image_msg1->encoding,
sensor_msgs::image_encodings::BGR8,
result_image).toImageMsg());

} catch (cv::Exception& e) {
Expand Down

0 comments on commit e81b9d1

Please sign in to comment.