Why do I get inverted colors in my images?
I am fetching images from a camera/webcam and publishing it's images using image_transport
.
When viewed in RViz the images look correct however when recorded with rosbag the compressed
image shows inverted colors.
Here is the node to record the images:
#include <ros/ros.h>
#include <image_transport/image_transport.h>
#include <opencv2/highgui/highgui.hpp>
#pragma GCC diagnostic ignored "-Wunused-parameter"
#include <cv_bridge/cv_bridge.h>
#pragma GCC diagnostic pop
int main(int argc,
char** argv)
{
ros::init(argc, argv, "image_publisher");
ros::NodeHandle nh;
image_transport::ImageTransport it(nh);
image_transport::Publisher pub = it.advertise("camera", 1);
cv::VideoCapture cap;
if (!cap.open(0))
return 1;
ros::Rate loop_rate(25);
while (nh.ok())
{
cv::Mat frame;
cap >> frame;
if (frame.empty())
break;
sensor_msgs::ImagePtr msg = cv_bridge::CvImage(std_msgs::Header(), "bgr8", frame).toImageMsg();
pub.publish(msg);
ros::spinOnce();
loop_rate.sleep();
}
return 0;
}
Minimal example package: https://gitlab.com/InstitutMaupertuis...
RViz
rqt_bag
Why are the colors inverted in the compressed image when reading the bag file?
Hello there! Are you sure your format to output these images is "bgr8" and not "rgb8"? This is a typical issue because how openCV handles images, inverting order of input channels of colors. I am not but you can try and give us feedback.
@CesarHoyosM I think so while not being 100% sure. If I use
rgb8
then the colors are inverted in RViz and in theraw
image in the bag file, but then thecompressed
image has the right colors. In short: this inverts the problem