Skip to content

Commit

Permalink
feat: add fuzzing harnesses
Browse files Browse the repository at this point in the history
  • Loading branch information
Christopher Krah committed May 23, 2024
1 parent 1ac02c4 commit e9c9b14
Show file tree
Hide file tree
Showing 4 changed files with 280 additions and 48 deletions.
119 changes: 71 additions & 48 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -47,8 +47,7 @@ if(NOT CMAKE_CXX_STANDARD)
endif()

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic
)
add_compile_options(-Wall -Wextra -Wpedantic)
endif()

set(opencv_version 4)
Expand Down Expand Up @@ -86,34 +85,62 @@ if(NOT OpenCV_FOUND)
find_package(OpenCV 3 REQUIRED COMPONENTS imgproc highgui)
endif()


if (BUILD_GSTREAMER)
pkg_check_modules(GST REQUIRED IMPORTED_TARGET gstreamer-1.0)
include_directories(SYSTEM ${GST_INCLUDE_DIRS})
link_directories(${GST_LIBRARY_DIRS})
pkg_check_modules(GST REQUIRED IMPORTED_TARGET gstreamer-1.0)
include_directories(SYSTEM ${GST_INCLUDE_DIRS})
link_directories(${GST_LIBRARY_DIRS})
endif()

include_directories(include)

set(camera_dependencies
rclcpp
sensor_msgs
stereo_msgs
geometry_msgs
std_msgs
vision_msgs
rclcpp_components
camera_info_manager
cv_bridge
image_transport
rclcpp
sensor_msgs
stereo_msgs
geometry_msgs
std_msgs
vision_msgs
rclcpp_components
camera_info_manager
cv_bridge
image_transport
)

FILE(GLOB LIB_SRC
"src/ImageConverter.cpp"
"src/ImgDetectionConverter.cpp"
"src/ImuConverter.cpp"
"src/ImageConverter.cpp"
"src/ImgDetectionConverter.cpp"
"src/ImuConverter.cpp"
)

option(FUZZING "Enable fuzzing mode" OFF)

if(FUZZING)
# Enable fuzzing and sanitizers
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -fsanitize=fuzzer,address,undefined -ggdb -O2")
set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} -fsanitize=fuzzer,address,undefined -ggdb -O2")
set(CMAKE_SHARED_LINKER_FLAGS "${CMAKE_SHARED_LINKER_FLAGS} -fsanitize=fuzzer,address,undefined -ggdb -O2")

# Add the depthai_bridge library
add_library(depthai_bridge SHARED ${LIB_SRC})
ament_target_dependencies(depthai_bridge PUBLIC ${camera_dependencies})
target_link_libraries(depthai_bridge PUBLIC depthai::core opencv_imgproc opencv_highgui)

# NOTE: This is copied from below as it enables correct compilation for
# the `ImgDetectionConverter.cpp`
target_compile_definitions(depthai_bridge PRIVATE IS_HUMBLE)

add_executable(img_conv_fuzz fuzz/img_conv_fuzz.cc)
target_link_libraries(img_conv_fuzz PRIVATE depthai_bridge)
add_executable(imu_conv_fuzz fuzz/imu_conv_fuzz.cc)
target_link_libraries(imu_conv_fuzz PRIVATE depthai_bridge)
add_executable(img_det_conv_fuzz fuzz/img_det_conv_fuzz.cc)
target_link_libraries(img_det_conv_fuzz PRIVATE depthai_bridge)

# Stop after building the fuzz target
return()
endif()

# Regular build process continues here
add_library(depthai_bridge SHARED ${LIB_SRC})
ament_target_dependencies(depthai_bridge PUBLIC ${camera_dependencies})
target_link_libraries(depthai_bridge PUBLIC depthai-core opencv_imgproc opencv_highgui)
Expand All @@ -134,7 +161,6 @@ add_library(depthai_camera SHARED src/depthai_camera.cpp)
ament_target_dependencies(depthai_camera PUBLIC ${camera_dependencies})
target_link_libraries(depthai_camera PUBLIC depthai-core opencv_imgproc opencv_highgui depthai_bridge)


# DepthAI Camera as separate node
add_executable(camera_node src/camera_node.cpp)
ament_target_dependencies(camera_node PUBLIC rclcpp rclcpp_components)
Expand All @@ -145,32 +171,31 @@ add_dependencies(camera_node depthai_camera)
rclcpp_components_register_nodes(depthai_camera PLUGIN "${PROJECT_NAME}::DepthAICamera" EXECUTABLE depthai_camera)

if (BUILD_GSTREAMER)
# DepthAI GStreamer as Component library
add_library(gstreamer_interface SHARED src/gstreamer_interface.cpp)
ament_target_dependencies(gstreamer_interface PUBLIC rclcpp std_msgs sensor_msgs)
target_link_libraries(gstreamer_interface PUBLIC ${GST_LIBRARIES} gstapp-1.0)

# DepthAI GStreamer as Component library
add_library(depthai_gstreamer SHARED src/depthai_gstreamer.cpp)
ament_target_dependencies(depthai_gstreamer PUBLIC rclcpp std_msgs sensor_msgs rclcpp_components)
target_link_libraries(depthai_gstreamer PUBLIC ${GST_LIBRARIES} gstapp-1.0 gstreamer_interface)

# DepthAI GStreamer as separate node
add_executable(gstreamer_node src/gstreamer_node.cpp)
ament_target_dependencies(gstreamer_node PUBLIC rclcpp rclcpp_components)
target_link_libraries(gstreamer_node PUBLIC depthai_gstreamer)
# Combined DepthAI node
add_executable(depthai_ctrl src/depthai_ctrl.cpp)
ament_target_dependencies(depthai_ctrl PUBLIC rclcpp rclcpp_components)
target_link_libraries(depthai_ctrl PUBLIC depthai_camera depthai_gstreamer)

add_dependencies(depthai_ctrl depthai_gstreamer depthai_camera)
add_dependencies(gstreamer_node depthai_gstreamer)
rclcpp_components_register_nodes(depthai_gstreamer PLUGIN "${PROJECT_NAME}::DepthAIGStreamer" EXECUTABLE depthai_gstreamer)
# DepthAI GStreamer as Component library
add_library(gstreamer_interface SHARED src/gstreamer_interface.cpp)
ament_target_dependencies(gstreamer_interface PUBLIC rclcpp std_msgs sensor_msgs)
target_link_libraries(gstreamer_interface PUBLIC ${GST_LIBRARIES} gstapp-1.0)

# DepthAI GStreamer as Component library
add_library(depthai_gstreamer SHARED src/depthai_gstreamer.cpp)
ament_target_dependencies(depthai_gstreamer PUBLIC rclcpp std_msgs sensor_msgs rclcpp_components)
target_link_libraries(depthai_gstreamer PUBLIC ${GST_LIBRARIES} gstapp-1.0 gstreamer_interface)

# DepthAI GStreamer as separate node
add_executable(gstreamer_node src/gstreamer_node.cpp)
ament_target_dependencies(gstreamer_node PUBLIC rclcpp rclcpp_components)
target_link_libraries(gstreamer_node PUBLIC depthai_gstreamer)

# Combined DepthAI node
add_executable(depthai_ctrl src/depthai_ctrl.cpp)
ament_target_dependencies(depthai_ctrl PUBLIC rclcpp rclcpp_components)
target_link_libraries(depthai_ctrl PUBLIC depthai_camera depthai_gstreamer)

add_dependencies(depthai_ctrl depthai_gstreamer depthai_camera)
add_dependencies(gstreamer_node depthai_gstreamer)
rclcpp_components_register_nodes(depthai_gstreamer PLUGIN "${PROJECT_NAME}::DepthAIGStreamer" EXECUTABLE depthai_gstreamer)
endif()



# Disable tests as its obsolete
# if (BUILD_TESTING)
# enable_testing()
Expand Down Expand Up @@ -214,9 +239,7 @@ install(TARGETS
camera_node
DESTINATION lib/${PROJECT_NAME})


install(DIRECTORY launch params urdf
DESTINATION share/${PROJECT_NAME}
)
DESTINATION share/${PROJECT_NAME})

ament_package()
ament_package()
91 changes: 91 additions & 0 deletions fuzz/img_conv_fuzz.cc
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;
}
62 changes: 62 additions & 0 deletions fuzz/img_det_conv_fuzz.cc
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;
}
56 changes: 56 additions & 0 deletions fuzz/imu_conv_fuzz.cc
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;
}

0 comments on commit e9c9b14

Please sign in to comment.