Blocks.ROSCamera

 1import numpy as np
 2import rospy
 3from cv_bridge import CvBridge
 4from sensor_msgs.msg import Image
 5
 6bridge = CvBridge()
 7img = None
 8
 9def callback(msg):
10    global img
11    img = np.asarray(bridge.imgmsg_to_cv2(msg, "bgr8"), dtype=np.uint8)
12
13def main(inputs, outputs, parameters, synchronise):
14    '''
15    ## Gets Image from a ROSCamera
16    The camera topic is read from the `ROSTopic` parameter, by default it is `/robot/camera`\n
17
18    The image message is converted to OpenCV compatible format via the `imgmsg_to_cv2()` function.
19    
20    This is then shared ahead using the `share_image()` function.
21    
22    **Inputs**: None
23
24    **Outputs**: BGR Image
25
26    **Parameters**: ROSTopic
27    '''
28    auto_enable = False
29    try:
30        enable = inputs.read_number("Enable")
31    except Exception:
32        auto_enable = True
33
34    rospy.init_node("camera_ros", anonymous=True)
35    subscriber_name = parameters.read_string("ROSTopic")
36    camera_subscriber = rospy.Subscriber(subscriber_name, Image, callback)
37
38    while(auto_enable or inputs.read_number('Enable') and not rospy.is_shutdown()):
39        if img is None:
40            continue
41        
42        outputs.share_image("Out", img)
43        synchronise()
def callback(msg)
10def callback(msg):
11    global img
12    img = np.asarray(bridge.imgmsg_to_cv2(msg, "bgr8"), dtype=np.uint8)
def main(inputs, outputs, parameters, synchronise)
14def main(inputs, outputs, parameters, synchronise):
15    '''
16    ## Gets Image from a ROSCamera
17    The camera topic is read from the `ROSTopic` parameter, by default it is `/robot/camera`\n
18
19    The image message is converted to OpenCV compatible format via the `imgmsg_to_cv2()` function.
20    
21    This is then shared ahead using the `share_image()` function.
22    
23    **Inputs**: None
24
25    **Outputs**: BGR Image
26
27    **Parameters**: ROSTopic
28    '''
29    auto_enable = False
30    try:
31        enable = inputs.read_number("Enable")
32    except Exception:
33        auto_enable = True
34
35    rospy.init_node("camera_ros", anonymous=True)
36    subscriber_name = parameters.read_string("ROSTopic")
37    camera_subscriber = rospy.Subscriber(subscriber_name, Image, callback)
38
39    while(auto_enable or inputs.read_number('Enable') and not rospy.is_shutdown()):
40        if img is None:
41            continue
42        
43        outputs.share_image("Out", img)
44        synchronise()

Block Description

Gets Image from a ROSCamera

The camera topic is read from the ROSTopic parameter, by default it is /robot/camera

The image message is converted to OpenCV compatible format via the imgmsg_to_cv2() function.

This is then shared ahead using the share_image() function.

Inputs: None

Outputs: BGR Image

Parameters: ROSTopic