Experimental Features
Features listed here aren’t released to the main beta image.
Computer Vision
The experimental vision branch launches a camera stream node when starting the robot. The image stream is available in the ROS topic namespace /rgb_camera
.
Following cameras are currently supported
ELP 2.0MP USB camera, ELP-USBFHD06H-BL36
At the moment, the camera must be plugged in when starting the robot system, however, later disconnects will not cause problems.
View camera image
To view the camera open rqt_image_view tool:
roslauch rqt_image_view rqt_image_view
Select /rgb_camera/image_raw
in the topleft combo box.
Capture a single image from the camera stream
The following example demonstrates how to capture a single image from the camera stream. Note that OpenCV is only used in this context to save the captured image to the disk. Also be aware that a camera with auto-exposure enabled will need time to adapt to the light conditions after startup, so the captured image might be over or under-exposed.
set_units("mm", "deg")
import os
import rospy
from sensor_msgs.msg import Image
from cv_bridge import CvBridge, CvBridgeError
import cv2
bridge = CvBridge()
def get_image():
# receive a single image from our camera node
# note that this will be the first image capture on the camera
# this can lead to over or under exposure if auto-exposure is enabled
# to get more stable image results, it is necessary to open an image stream
image = rospy.wait_for_message("/rgb_camera/image_raw", Image, timeout=rospy.Duration.from_sec(10.0))
try:
# Convert your ROS Image message to OpenCV2
cv2_img = bridge.imgmsg_to_cv2(image, "bgr8")
except CvBridgeError as e:
notify(f"Error converting image {e}", warning=True)
else:
# Save your OpenCV2 image as a jpeg
name = os.path.join(os.getcwd(), 'camera_image.jpg')
cv2.imwrite(name, cv2_img)
notify("Captured image", image_path=name, warning=True)
def main():
get_image()
exit()
Capture image from the camera stream
TODO
Detect AR track markers
TODO