Skip to content

Commit

Permalink
Merge pull request #137 from peci1/patch-3
Browse files Browse the repository at this point in the history
Added basic input checking for RVL
  • Loading branch information
ijnek authored Feb 23, 2023
2 parents c26d149 + f920fda commit cca6781
Showing 1 changed file with 18 additions and 0 deletions.
18 changes: 18 additions & 0 deletions compressed_depth_image_transport/src/codec.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -126,9 +126,27 @@ sensor_msgs::Image::Ptr decodeCompressedDepthImage(const sensor_msgs::Compressed
}
} else if (compression_format == "rvl") {
const unsigned char *buffer = imageData.data();

uint32_t cols, rows;
memcpy(&cols, &buffer[0], 4);
memcpy(&rows, &buffer[4], 4);
if (rows == 0 || cols == 0)
{
ROS_ERROR_THROTTLE(1.0, "Received malformed RVL-encoded image. Size %ix%i contains zero.", cols, rows);
return sensor_msgs::Image::Ptr();
}

// Sanity check - the best compression ratio is 4x; we leave some buffer, so we check whether the output image would
// not be more than 10x larger than the compressed one. If it is, we probably received corrupted data.
// The condition should be "numPixels * 2 > compressed.size() * 10" (because each pixel is 2 bytes), but to prevent
// overflow, we have canceled out the *2 from both sides of the inequality.
const auto numPixels = static_cast<uint64_t>(rows) * cols;
if (numPixels > std::numeric_limits<int>::max() || numPixels > static_cast<uint64_t>(imageData.size()) * 5)
{
ROS_ERROR_THROTTLE(1.0, "Received malformed RVL-encoded image. It reports size %ux%u.", cols, rows);
return sensor_msgs::Image::Ptr();
}

decompressed = Mat(rows, cols, CV_16UC1);
RvlCodec rvl;
rvl.DecompressRVL(&buffer[8], decompressed.ptr<unsigned short>(), cols * rows);
Expand Down

0 comments on commit cca6781

Please sign in to comment.