ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
I've thrown together this gist on github, which functions as a very basic Python image subscriber & saver: https://gist.github.com/rethink-imcmahon/77a1a4d5506258f3dc1f
It creates a ROS subscriber, saves a jpeg on image callback, and then overwrites it on every subsequent callback invocation (~15 Hz for Baxter's cameras).
The important takeaway is the flow from ROS Image -> CvBridge Converter -> OpenCV2 -> JPEG file:
#! /usr/bin/python
# Copyright (c) 2015, Rethink Robotics, Inc.
# Using this CvBridge Tutorial for converting
# ROS images to OpenCV2 images
# http://wiki.ros.org/cv_bridge/Tutorials/ConvertingBetweenROSImagesAndOpenCVImagesPython
# Using this OpenCV2 tutorial for saving Images:
# http://opencv-python-tutroals.readthedocs.org/en/latest/py_tutorials/py_gui/py_image_display/py_image_display.html
# rospy for the subscriber
import rospy
# ROS Image message
from sensor_msgs.msg import Image
# ROS Image message -> OpenCV2 image converter
from cv_bridge import CvBridge, CvBridgeError
# OpenCV2 for saving an image
import cv2
# Instantiate CvBridge
bridge = CvBridge()
def image_callback(msg):
print("Received an image!")
try:
# Convert your ROS Image message to OpenCV2
cv2_img = bridge.imgmsg_to_cv2(msg, "bgr8")
except CvBridgeError, e:
print(e)
# Save your OpenCV2 image as a jpeg
cv2.imwrite('camera_image.jpeg', cv2_img)
def main():
rospy.init_node('image_listener')
# Define your image topic
image_topic = "/cameras/left_hand_camera/image"
# Set up your subscriber and define its callback
rospy.Subscriber(image_topic, Image, image_callback)
# Spin until ctrl + c
rospy.spin()
if __name__ == '__main__':
main()
2 | No.2 Revision |
I've thrown together this gist on github, which functions as a very basic Python image subscriber & saver: https://gist.github.com/rethink-imcmahon/77a1a4d5506258f3dc1f
It creates a ROS subscriber, saves a jpeg on image callback, and then overwrites it on every subsequent callback invocation (~15 Hz for Baxter's cameras).
The important takeaway is the flow from ROS Image -> CvBridge Converter -> OpenCV2 -> JPEG file:
#! /usr/bin/python
# Copyright (c) 2015, Rethink Robotics, Inc.
# Using this CvBridge Tutorial for converting
# ROS images to OpenCV2 images
# http://wiki.ros.org/cv_bridge/Tutorials/ConvertingBetweenROSImagesAndOpenCVImagesPython
# Using this OpenCV2 tutorial for saving Images:
# http://opencv-python-tutroals.readthedocs.org/en/latest/py_tutorials/py_gui/py_image_display/py_image_display.html
# rospy for the subscriber
import rospy
# ROS Image message
from sensor_msgs.msg import Image
# ROS Image message -> OpenCV2 image converter
from cv_bridge import CvBridge, CvBridgeError
# OpenCV2 for saving an image
import cv2
# Instantiate CvBridge
bridge = CvBridge()
def image_callback(msg):
print("Received an image!")
try:
# Convert your ROS Image message to OpenCV2
cv2_img = bridge.imgmsg_to_cv2(msg, "bgr8")
except CvBridgeError, e:
print(e)
else:
# Save your OpenCV2 image as a jpeg
cv2.imwrite('camera_image.jpeg', cv2_img)
def main():
rospy.init_node('image_listener')
# Define your image topic
image_topic = "/cameras/left_hand_camera/image"
# Set up your subscriber and define its callback
rospy.Subscriber(image_topic, Image, image_callback)
# Spin until ctrl + c
rospy.spin()
if __name__ == '__main__':
main()