I wrote a function using opencv in order to do so.
LUcorner is the position of the upper-left corner of the image in rviz.
sizeSq is a scaling factor.
void sendImageToRviz(std::string frame_id, int id, ros::Publisher* marker_pub, cv::Mat src, double sizeSq, std::pair<double, double=""> LUcorner) {
visualization_msgs::Marker image;
image.header.frame_id = frame_id;
image.header.stamp = ros::Time::now();
image.ns = "image";
image.id = id;
image.action = visualization_msgs::Marker::ADD;
image.type = visualization_msgs::Marker::TRIANGLE_LIST;
image.scale.x = 1;
image.scale.y = 1;
image.scale.z = 1;
double pix = sizeSq / src.rows;
geometry_msgs::Point p;
std_msgs::ColorRGBA crgb;
for(int r = 0; r < src.rows; ++r) {
for(int c = 0; c < src.rows; ++c) {
cv::Vec3b intensity = src.at<cv::Vec3b>(r, c);
crgb.r = intensity.val[2] / 255.0;
crgb.g = intensity.val[1] / 255.0;
crgb.b = intensity.val[0] / 255.0;
crgb.a = 1.0;
p.z = 0;
p.x = LUcorner.first + r * pix;
p.y = LUcorner.second + c * pix;
image.points.push_back(p);
image.colors.push_back(crgb);
p.x = LUcorner.first + (r + 1) * pix;
p.y = LUcorner.second + c * pix;
image.points.push_back(p);
image.colors.push_back(crgb);
p.x = LUcorner.first + r * pix;
p.y = LUcorner.second + (c + 1) * pix;
image.points.push_back(p);
image.colors.push_back(crgb);
p.x = LUcorner.first + (r + 1) * pix;
p.y = LUcorner.second + c * pix;
image.points.push_back(p);
image.colors.push_back(crgb);
p.x = LUcorner.first + (r + 1) * pix;
p.y = LUcorner.second + (c + 1) * pix;
image.points.push_back(p);
image.colors.push_back(crgb);
p.x = LUcorner.first + r * pix;
p.y = LUcorner.second + (c + 1) * pix;
image.points.push_back(p);
image.colors.push_back(crgb);
}
}
marker_pub->publish(image);
}