Skip to content

Commit

Permalink
Add header arg to cv2_to_imgmsg (#326)
Browse files Browse the repository at this point in the history
  • Loading branch information
708yamaguchi authored Nov 23, 2021
1 parent 12889b7 commit c791220
Showing 1 changed file with 4 additions and 1 deletion.
5 changes: 4 additions & 1 deletion cv_bridge/python/cv_bridge/core.py
Original file line number Diff line number Diff line change
Expand Up @@ -226,7 +226,7 @@ def cv2_to_compressed_imgmsg(self, cvim, dst_format = "jpg"):

return cmprs_img_msg

def cv2_to_imgmsg(self, cvim, encoding = "passthrough"):
def cv2_to_imgmsg(self, cvim, encoding = "passthrough", header = None):
"""
Convert an OpenCV :cpp:type:`cv::Mat` type to a ROS sensor_msgs::Image message.
Expand All @@ -235,6 +235,7 @@ def cv2_to_imgmsg(self, cvim, encoding = "passthrough"):
* ``"passthrough"``
* one of the standard strings in sensor_msgs/image_encodings.h
:param header: A std_msgs.msg.Header message
:rtype: A sensor_msgs.msg.Image message
:raises CvBridgeError: when the ``cvim`` has a type that is incompatible with ``encoding``
Expand All @@ -251,6 +252,8 @@ def cv2_to_imgmsg(self, cvim, encoding = "passthrough"):
img_msg = sensor_msgs.msg.Image()
img_msg.height = cvim.shape[0]
img_msg.width = cvim.shape[1]
if header is not None:
img_msg.header = header
if len(cvim.shape) < 3:
cv_type = self.dtype_with_channels_to_cvtype2(cvim.dtype, 1)
else:
Expand Down

0 comments on commit c791220

Please sign in to comment.