Skip to content

Commit 9ac9434

Browse files
authored
Document not to access image data during a step. (cyberbotics#5859)
* Document not to access image data during a step. * Fix formatting.
1 parent 2c63f30 commit 9ac9434

4 files changed

Lines changed: 21 additions & 2 deletions

File tree

docs/reference/camera.md

Lines changed: 8 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -133,7 +133,9 @@ The pixel information can be obtained from the `wb_camera_get_image` function.
133133
The red, green and blue channels (RGB) can be extracted from the resulting image by the `wb_camera_image_get_*`-like functions.
134134

135135
Each time a camera is refreshed, an OpenGL rendering is performed, and the color information is copied into the buffer returned by the `wb_camera_get_image` function.
136-
The format of this buffers is BGRA (32 bits).
136+
The contents of the buffer are subject to change between a call to `wb_robot_step_begin` and the subsequent call to `wb_robot_step_end`.
137+
As a result, if you want to access the buffer during a step, you should copy it before the step begins and access the copy.
138+
The format of this buffer is BGRA (32 bits).
137139
We recommend to use the `wb_camera_image_get_*`-like functions to access the buffer because the internal format could change.
138140

139141
> **Note** [MATLAB]: The MATLAB API uses a language-specific representation of color images consisting of a 3D array of RGB triplets.
@@ -912,6 +914,8 @@ byte_size = camera_width * camera_height * 4
912914
```
913915

914916
Attempting to read outside the bounds of this chunk will cause an error.
917+
The contents of the image are subject to change between a call to `wb_robot_step_begin` and the subsequent call to `wb_robot_step_end`.
918+
As a result, if you want to access the image during a step, you should copy it before the step begins and access the copy.
915919
Internal pixel format of the buffer is BGRA (32 bits).
916920
Note that the Java API uses little-endian format and stores the pixel integer value in ARGB format.
917921

@@ -1098,6 +1102,9 @@ The `quality` parameter should be in the range 1 (worst quality) to 100 (best qu
10981102
Low quality JPEG files will use less disk space.
10991103
For PNG images, the `quality` parameter is ignored.
11001104

1105+
`wb_camera_save_image` should not be called between a call to `wb_robot_step_begin` and the subsequent call to `wb_robot_step_end`,
1106+
because the image is subject to change during that period.
1107+
11011108
The return value of the `wb_camera_save_image` function is 0 in case of success.
11021109
It is -1 in case of failure (unable to open the specified file or unrecognized image file extension).
11031110

docs/reference/lidar.md

Lines changed: 7 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -489,14 +489,17 @@ range = wb_lidar_get_layer_range_image(tag, layer)
489489

490490
##### Description
491491

492-
*get the range image and range image associate with a specific layer*
492+
*get the range image and range image associated with a specific layer*
493493

494494
The `wb_lidar_get_range_image` function allows the user to read the contents of the last range image grabbed by a lidar.
495+
It should not be called if the lidar was in point cloud mode during the most recent step.
495496
The range image is computed using the depth buffer produced by the OpenGL rendering.
496497
The range image is coded as an array of single precision floating point values corresponding to the range value of each pixel of the image.
497498
The precision of the lidar values decreases when the objects are located farther from the near clipping plane.
498499
Pixels are stored in scan lines running from left to right and from first to last layer.
499500
The memory chunk returned by this function shall not be freed, as it is managed by the lidar internally.
501+
The contents of the image are subject to change between a call to `wb_robot_step_begin` and the subsequent call to `wb_robot_step_end`.
502+
As a result, if you want to access the image during a step, you should copy it before the step begins and access the copy.
500503
The size in bytes of the range image can be computed as follows:
501504

502505
```
@@ -604,6 +607,7 @@ number_of_points = wb_lidar_get_number_of_points(tag)
604607
*get the points array, points array associate with a specific layer and total number of point*
605608

606609
The `wb_lidar_get_point_cloud` function returns the pointer to the point cloud array, each point consists of a [`WbLidarPoint`](#wblidarpoint).
610+
It should not be called unless the lidar was in point cloud mode during the most recent step.
607611
The memory chunk returned by this function shall not be freed, as it is managed by the lidar internally.
608612
The size in bytes of the point cloud can be computed as follows:
609613

@@ -612,6 +616,8 @@ size = lidar_number_of_points * sizeof(WbLidarPoint)
612616
```
613617

614618
Attempting to read outside the bounds of this memory chunk will cause an error.
619+
The contents of the point cloud are subject to change between a call to `wb_robot_step_begin` and the subsequent call to `wb_robot_step_end`.
620+
As a result, if you want to access the point cloud during a step, you should copy it before the step begins and access the copy.
615621

616622
The `wb_lidar_get_layer_point_cloud` function is a convenient way of getting directly the sub point cloud associated with one layer.
617623

docs/reference/rangefinder.md

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -545,6 +545,8 @@ The range image is coded as an array of single precision floating point values c
545545
The precision of the range-finder values decreases when the objects are located farther from the near clipping plane.
546546
Pixels are stored in scan lines running from left to right and from top to bottom.
547547
The memory chunk returned by this function shall not be freed, as it is managed by the range-finder internally.
548+
The contents of the image are subject to change between a call to `wb_robot_step_begin` and the subsequent call to `wb_robot_step_end`.
549+
As a result, if you want to access the image during a step, you should copy it before the step begins and access the copy.
548550
The size in bytes of the range image can be computed as follows:
549551

550552
```
@@ -666,5 +668,7 @@ HDR images are saved as 32-bit floating-point single-channel images.
666668
For PNG and JPEG, depth data is stored in the range `0` to `255`.
667669
This depth data can thus be extracted for further use by reading the image file.
668670

671+
`wb_range_finder_save_image` should not be called between a call to `wb_robot_step_begin` and the subsequent call to `wb_robot_step_end`, because the image is subject to change during that period.
672+
669673
The return value of the `wb_range_finder_save_image` function is 0 in case of success.
670674
It is -1 in case of failure (unable to open the specified file or unrecognized image file extension).

docs/reference/robot.md

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -265,6 +265,8 @@ You can simply call them before `wb_robot_step_begin` or after `wb_robot_step_en
265265
However, some of these functions can be called between `wb_robot_step_begin` and `wb_robot_step_end` if you enable the supervisor tracking feature.
266266
`wb_supervisor_field_enable_sf_tracking`, `wb_supervisor_node_enable_pose_tracking` and `wb_supervisor_node_enable_contact_point_tracking` force Webots to continuously stream the requested information to the controller.
267267
By enabling the tracking, the corresponding supervisor functions can be called between `wb_robot_step_begin` and `wb_robot_step_end`, because their value will be queried to Webots during `wb_robot_step_begin` and received during `wb_robot_step_end`.
268+
Also, note that the data returned by the following functions are subject to change between a call to `wb_robot_step_begin` and the subsequent call to `wb_robot_step_end`: `wb_camera_get_image`, `wb_camera_recognition_get_segmentation_image`, `wb_lidar_get_range_image`, `wb_lidar_get_layer_range_image`, `wb_lidar_get_point_cloud`, `wb_lidar_get_layer_point_cloud`, and `wb_range_finder_get_range_image`.
269+
As a result, if you want to access that data during a step, you should copy it before the step begins and access the copy.
268270

269271
The C API has two additional functions: `wb_robot_init` and `wb_robot_cleanup`.
270272
There is no equivalent of the `wb_robot_init` and `wb_robot_cleanup` functions in the Java, Python, C++ and MATLAB APIs.

0 commit comments

Comments
 (0)