Video camera¶

A camera capturing RGBA image
This sensor emulates a single video camera. It generates a series of RGBA images. Images are encoded as binary char arrays, with 4 bytes per pixel.
Camera calibration matrix¶
The camera configuration parameters implicitly define a geometric camera in blender units. Knowing that the cam_focal attribute is a value that represents the distance in Blender unit at which the largest image dimension is 32.0 Blender units, the camera intrinsic calibration matrix is defined as
alpha_u | 0 | u_0 |
0 | alpha_v | v_0 |
0 | 0 | 1 |
where:
- alpha_u == alpha_v = cam_width . cam_focal / 32 (we suppose here that cam_width > cam_height. If not, then use cam_height in the formula)
- u_0 = cam_width / 2
- v_0 = cam_height / 2
See also Generic Camera for generic informations about Morse cameras.
Configuration parameters for Video camera¶
You can set these properties in your scripts with <component>.properties(<property1>=..., <property2>=...)
.
cam_width
(default:256
)- (no documentation available yet)
cam_height
(default:256
)- (no documentation available yet)
cam_focal
(default:25.0
)- (no documentation available yet)
cam_fov
(default:None
)- (no documentation available yet)
cam_near
(default:0.1
)- (no documentation available yet)
cam_far
(default:100.0
)- (no documentation available yet)
Vertical_Flip
(default:True
)- (no documentation available yet)
retrieve_depth
(default:False
)- (no documentation available yet)
retrieve_zbuffer
(default:False
)- (no documentation available yet)
Data fields¶
This sensor exports these datafields at each simulation step:
timestamp
(float, initial value:0.0
)- number of seconds in simulated time
image
(buffer, initial value:none
)- The data captured by the camera, stored as a Python Buffer class object. The data is of size
(cam_width * cam_height * 4)
bytes. The image is stored as RGBA.
intrinsic_matrix
(mat3<float>, initial value:none
)- The intrinsic calibration matrix, stored as a 3x3 row major Matrix.
Interface support:
ros
as sensor_msgs/Image (morse.middleware.ros.video_camera.VideoCameraPublisher
)socket
as base64 encoded RGBA image (morse.middleware.sockets.video_camera.VideoCameraPublisher
)yarp
as YarpImagePublisher (morse.middleware.yarp.video_camera.YarpImagePublisher
)pocolibs
as ViamImageBank (morse.middleware.pocolibs.sensors.viam.ViamPoster
)
Services for Video camera¶
capture(n)
(non blocking)Capture n images
- Parameters
n
: the number of images to take. A negative number means take image indefinitely
get_configurations()
(blocking)Returns the configurations of a component (parsed from the properties).
Return value
a dictionary of the current component’s configurations
get_local_data()
(blocking)Returns the current data stored in the sensor.
Return value
a dictionary of the current sensor’s data
get_properties()
(blocking)Returns the properties of a component.
Return value
a dictionary of the current component’s properties
set_property(prop_name, prop_val)
(blocking)Modify one property on a component
Parameters
prop_name
: the name of the property to modify (as shown the documentation)prop_val
: the new value of the property. Note that there is no checking about the type of the value so be careful
Return value
nothing
Examples¶
The following examples show how to use this component in a Builder script:
from morse.builder import *
# adds a default robot (the MORSE mascott!)
robot = Morsy()
# creates a new instance of the sensor
videocamera = VideoCamera()
# place your component at the correct location
videocamera.translate(<x>, <y>, <z>)
videocamera.rotate(<rx>, <ry>, <rz>)
robot.append(videocamera)
# define one or several communication interface, like 'socket'
videocamera.add_interface(<interface>)
env = Environment('empty')
Other sources of examples¶
(This page has been auto-generated from MORSE module morse.sensors.video_camera.)