-
Notifications
You must be signed in to change notification settings - Fork 1
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
- Loading branch information
Christopher Krah
committed
May 23, 2024
1 parent
1ac02c4
commit e9c9b14
Showing
4 changed files
with
280 additions
and
48 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,91 @@ | ||
#include <cstdint> | ||
#include <cv_bridge/cv_bridge.hpp> | ||
#include <fuzzer/FuzzedDataProvider.h> | ||
|
||
#include "depthai-shared/common/CameraInfo.hpp" | ||
#include <depthai/depthai.hpp> | ||
#include <depthai_ctrl/ImageConverter.hpp> | ||
#include <depthai_ctrl/ImgDetectionConverter.hpp> | ||
#include <depthai_ctrl/ImuConverter.hpp> | ||
#include <deque> | ||
#include <iostream> | ||
#include <memory> | ||
#include <opencv4/opencv2/core.hpp> | ||
#include <opencv4/opencv2/core/hal/interface.h> | ||
#include <ratio> | ||
#include <tuple> | ||
#include <vector> | ||
|
||
extern "C" int LLVMFuzzerTestOneInput(const uint8_t *Data, size_t Size) { | ||
FuzzedDataProvider dataProvider(Data, Size); | ||
|
||
auto inData = std::make_shared<dai::ImgFrame>(); | ||
|
||
unsigned int width = dataProvider.ConsumeIntegral<int64_t>(); | ||
unsigned int height = dataProvider.ConsumeIntegral<int64_t>(); | ||
unsigned int channelSize = dataProvider.ConsumeIntegral<int64_t>(); | ||
size_t imageSize = width * height * channelSize; | ||
std::vector<uint8_t> frameData = | ||
dataProvider.ConsumeBytes<uint8_t>(imageSize); | ||
|
||
// Set the generated data to the ImgFrame object | ||
inData->setWidth(width); | ||
inData->setHeight(height); | ||
inData->setData(frameData); | ||
|
||
// NOTE: Check if inData is populated | ||
// Otherwise we're triggering an assert: | ||
// what(): OpenCV(4.6.0) ./modules/imgcodecs/src/loadsave.cpp:816: error: | ||
// (-215:Assertion failed) !buf.empty() in function 'imdecode_' | ||
if (inData->getData().empty()) { | ||
return 1; | ||
} | ||
|
||
// NOTE: Another sanity check for: | ||
// what(): OpenCV(4.6.0) | ||
// /usr/include/opencv4/opencv2/core/utility.hpp:627: error: | ||
// (-215:Assertion failed) !empty() in function 'forEach_impl' | ||
if (width <= 0 || height <= 0) { | ||
return 1; | ||
} | ||
|
||
std::deque<dai::ros::ImageMsgs::Image> outImageMsgs; | ||
dai::RawImgFrame::Type type; | ||
switch (dataProvider.ConsumeIntegralInRange(0, 2)) { | ||
case 0: | ||
type = dai::RawImgFrame::Type::RAW8; | ||
inData->setType(type); | ||
break; | ||
case 1: | ||
type = dai::RawImgFrame::Type::GRAY8; | ||
inData->setType(type); | ||
break; | ||
case 2: | ||
type = dai::RawImgFrame::Type::BGR888i; | ||
inData->setType(type); | ||
break; | ||
default: | ||
return 0; | ||
} | ||
sensor_msgs::msg::CameraInfo info; | ||
std::string frameName = dataProvider.ConsumeRandomLengthString(); | ||
bool interleaved = dataProvider.ConsumeBool(); | ||
|
||
dai::ros::ImageConverter imageConverter(frameName, interleaved); | ||
|
||
try { | ||
imageConverter.toRosMsgFromBitStream(inData, outImageMsgs, type, info); | ||
} catch (const cv::Exception &e) { | ||
return -1; | ||
} | ||
|
||
// Check if the output image messages are valid | ||
for (const auto &msg : outImageMsgs) { | ||
if (msg.width <= 0 || msg.height <= 0 || msg.encoding.empty()) { | ||
// Invalid output image message | ||
return -1; | ||
} | ||
} | ||
|
||
return 0; | ||
} |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,62 @@ | ||
#include <cv_bridge/cv_bridge.hpp> | ||
#include <fuzzer/FuzzedDataProvider.h> | ||
|
||
#include "depthai-shared/common/CameraInfo.hpp" | ||
#include <depthai/depthai.hpp> | ||
#include <depthai_ctrl/ImageConverter.hpp> | ||
#include <depthai_ctrl/ImgDetectionConverter.hpp> | ||
#include <depthai_ctrl/ImuConverter.hpp> | ||
#include <deque> | ||
#include <memory> | ||
#include <ratio> | ||
#include <tuple> | ||
|
||
extern "C" int LLVMFuzzerTestOneInput(const uint8_t *Data, size_t Size) { | ||
FuzzedDataProvider dataProvider(Data, Size); | ||
|
||
std::string frameName = dataProvider.ConsumeRandomLengthString(); | ||
int width = dataProvider.ConsumeIntegral<int>(); | ||
int height = dataProvider.ConsumeIntegral<int>(); | ||
bool normalized = dataProvider.ConsumeBool(); | ||
|
||
dai::ros::ImgDetectionConverter detectionConverter(frameName, width, height, | ||
normalized); | ||
|
||
auto inNetData = std::make_shared<dai::ImgDetections>(); | ||
|
||
// Determine the number of detections to generate | ||
size_t numDetections = dataProvider.ConsumeIntegralInRange<size_t>(0, 10); | ||
|
||
// Generate random detections and add them to inNetData->detections | ||
for (size_t i = 0; i < numDetections; ++i) { | ||
dai::ImgDetection detection; | ||
|
||
detection.label = dataProvider.ConsumeIntegral<int>(); | ||
detection.confidence = dataProvider.ConsumeFloatingPoint<float>(); | ||
detection.xmin = dataProvider.ConsumeFloatingPoint<float>(); | ||
detection.ymin = dataProvider.ConsumeFloatingPoint<float>(); | ||
detection.xmax = dataProvider.ConsumeFloatingPoint<float>(); | ||
detection.ymax = dataProvider.ConsumeFloatingPoint<float>(); | ||
|
||
inNetData->detections.push_back(detection); | ||
} | ||
|
||
auto timestamp = | ||
std::chrono::steady_clock::time_point(std::chrono::steady_clock::duration( | ||
dataProvider.ConsumeIntegral<int64_t>())); | ||
inNetData->setTimestamp(timestamp); | ||
|
||
auto timestampDevice = | ||
std::chrono::steady_clock::time_point(std::chrono::steady_clock::duration( | ||
dataProvider.ConsumeIntegral<int64_t>())); | ||
inNetData->setTimestampDevice(timestampDevice); | ||
|
||
inNetData->setSequenceNum(dataProvider.ConsumeIntegral<int64_t>()); | ||
|
||
std::deque<dai::ros::VisionMsgs::Detection2DArray> opDetectionMsgs; | ||
|
||
detectionConverter.toRosMsg(inNetData, opDetectionMsgs); | ||
auto rosMsgPtr = detectionConverter.toRosMsgPtr(inNetData); | ||
|
||
return 0; | ||
} |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,56 @@ | ||
#include <cv_bridge/cv_bridge.hpp> | ||
#include <fuzzer/FuzzedDataProvider.h> | ||
|
||
#include "depthai-shared/common/CameraInfo.hpp" | ||
#include <depthai/depthai.hpp> | ||
#include <depthai_ctrl/ImageConverter.hpp> | ||
#include <depthai_ctrl/ImgDetectionConverter.hpp> | ||
#include <depthai_ctrl/ImuConverter.hpp> | ||
#include <deque> | ||
#include <memory> | ||
#include <ratio> | ||
#include <tuple> | ||
|
||
extern "C" int LLVMFuzzerTestOneInput(const uint8_t *Data, size_t Size) { | ||
FuzzedDataProvider dataProvider(Data, Size); | ||
|
||
std::string frameName = dataProvider.ConsumeRandomLengthString(); | ||
|
||
auto inData = std::make_shared<dai::IMUData>(); | ||
// NOTE: Starting from 0 leads to an OOB access | ||
size_t numPackets = dataProvider.ConsumeIntegralInRange<size_t>(1, 10); | ||
|
||
// Generate random packets and add them to inData->packets | ||
for (size_t i = 0; i < numPackets; ++i) { | ||
dai::IMUPacket packet; | ||
|
||
// Populate the fields of IMUPacket | ||
packet.acceleroMeter.x = dataProvider.ConsumeFloatingPoint<float>(); | ||
packet.acceleroMeter.y = dataProvider.ConsumeFloatingPoint<float>(); | ||
packet.acceleroMeter.z = dataProvider.ConsumeFloatingPoint<float>(); | ||
|
||
packet.gyroscope.x = dataProvider.ConsumeFloatingPoint<float>(); | ||
packet.gyroscope.y = dataProvider.ConsumeFloatingPoint<float>(); | ||
packet.gyroscope.z = dataProvider.ConsumeFloatingPoint<float>(); | ||
|
||
packet.magneticField.x = dataProvider.ConsumeFloatingPoint<float>(); | ||
packet.magneticField.y = dataProvider.ConsumeFloatingPoint<float>(); | ||
packet.magneticField.z = dataProvider.ConsumeFloatingPoint<float>(); | ||
|
||
packet.rotationVector.i = dataProvider.ConsumeFloatingPoint<float>(); | ||
packet.rotationVector.j = dataProvider.ConsumeFloatingPoint<float>(); | ||
packet.rotationVector.k = dataProvider.ConsumeFloatingPoint<float>(); | ||
packet.rotationVector.real = dataProvider.ConsumeFloatingPoint<float>(); | ||
packet.rotationVector.rotationVectorAccuracy = | ||
dataProvider.ConsumeFloatingPoint<float>(); | ||
|
||
inData->packets.push_back(packet); | ||
} | ||
|
||
dai::ros::ImuConverter imuConverter(frameName); | ||
dai::ros::ImuMsgs::Imu outImuMsg; | ||
imuConverter.toRosMsg(inData, outImuMsg); | ||
auto rosMsgPtr = imuConverter.toRosMsgPtr(inData); | ||
|
||
return 0; | ||
} |