You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
if (color_pixel[1] < 0.0f || color_pixel[1] > image_color.rows
|| color_pixel[0] < 0.0f || color_pixel[0] > image_color.cols)
{
// For out of bounds color data, default to a shade of blue in order to visually distinguish holes.// This color value is same as the librealsense out of bounds color value.
*iter_r = static_cast<uint8_t>(96);
*iter_g = static_cast<uint8_t>(157);
*iter_b = static_cast<uint8_t>(198);
}
else
{
int i = static_cast<int>(color_pixel[0]);
int j = static_cast<int>(color_pixel[1]);
*iter_r = static_cast<uint8_t>(color_data[i * 3 + j * image_color.cols * 3]);
*iter_g = static_cast<uint8_t>(color_data[i * 3 + j * image_color.cols * 3 + 1]);
*iter_b = static_cast<uint8_t>(color_data[i * 3 + j * image_color.cols * 3 + 2]);
}
Causes a segmentation fault because from time to time color_pixel[1] == image_color.rows or color_pixel[0] == image_color.cols.
The image access in the else clause is then out of bounds by 1 pixel, and librealsense_camera_nodelet.so segfaults as a result.
The text was updated successfully, but these errors were encountered:
* fix issue #335 according to solution lsolanka as suggested in pull request #336.
* moving all the properties and material definitions inside the macro as suggested by @felixvd
* add compilation flag SET_USER_BREAK_AT_STARTUP to create user waiting point for debugging purposes.
add reading from bagfile option by using <rosbag_filename> parameter in launch file.
base_realsense_node.cpp: add option - by specifying width, height or fps as 0, pick up on the first sensor profile available.
scripts/rs2_listener.py, rs2_test.py - initial version for file based, standalone unitest.
* add .travis.yml file
With my R200, for some reason this code:
Causes a segmentation fault because from time to time color_pixel[1] == image_color.rows or color_pixel[0] == image_color.cols.
The image access in the else clause is then out of bounds by 1 pixel, and librealsense_camera_nodelet.so segfaults as a result.
The text was updated successfully, but these errors were encountered: