From e9c9b145724d9946c93a6ee937502614b355576a Mon Sep 17 00:00:00 2001 From: Christopher Krah Date: Thu, 23 May 2024 09:31:29 +0400 Subject: [PATCH] feat: add fuzzing harnesses --- CMakeLists.txt | 119 +++++++++++++++++++++++--------------- fuzz/img_conv_fuzz.cc | 91 +++++++++++++++++++++++++++++ fuzz/img_det_conv_fuzz.cc | 62 ++++++++++++++++++++ fuzz/imu_conv_fuzz.cc | 56 ++++++++++++++++++ 4 files changed, 280 insertions(+), 48 deletions(-) create mode 100644 fuzz/img_conv_fuzz.cc create mode 100644 fuzz/img_det_conv_fuzz.cc create mode 100644 fuzz/imu_conv_fuzz.cc diff --git a/CMakeLists.txt b/CMakeLists.txt index 615327b..36b20fd 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -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) @@ -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) @@ -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) @@ -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() @@ -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() \ No newline at end of file +ament_package() diff --git a/fuzz/img_conv_fuzz.cc b/fuzz/img_conv_fuzz.cc new file mode 100644 index 0000000..f9d4903 --- /dev/null +++ b/fuzz/img_conv_fuzz.cc @@ -0,0 +1,91 @@ +#include +#include +#include + +#include "depthai-shared/common/CameraInfo.hpp" +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +extern "C" int LLVMFuzzerTestOneInput(const uint8_t *Data, size_t Size) { + FuzzedDataProvider dataProvider(Data, Size); + + auto inData = std::make_shared(); + + unsigned int width = dataProvider.ConsumeIntegral(); + unsigned int height = dataProvider.ConsumeIntegral(); + unsigned int channelSize = dataProvider.ConsumeIntegral(); + size_t imageSize = width * height * channelSize; + std::vector frameData = + dataProvider.ConsumeBytes(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 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; +} diff --git a/fuzz/img_det_conv_fuzz.cc b/fuzz/img_det_conv_fuzz.cc new file mode 100644 index 0000000..384c66d --- /dev/null +++ b/fuzz/img_det_conv_fuzz.cc @@ -0,0 +1,62 @@ +#include +#include + +#include "depthai-shared/common/CameraInfo.hpp" +#include +#include +#include +#include +#include +#include +#include +#include + +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 height = dataProvider.ConsumeIntegral(); + bool normalized = dataProvider.ConsumeBool(); + + dai::ros::ImgDetectionConverter detectionConverter(frameName, width, height, + normalized); + + auto inNetData = std::make_shared(); + + // Determine the number of detections to generate + size_t numDetections = dataProvider.ConsumeIntegralInRange(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(); + detection.confidence = dataProvider.ConsumeFloatingPoint(); + detection.xmin = dataProvider.ConsumeFloatingPoint(); + detection.ymin = dataProvider.ConsumeFloatingPoint(); + detection.xmax = dataProvider.ConsumeFloatingPoint(); + detection.ymax = dataProvider.ConsumeFloatingPoint(); + + inNetData->detections.push_back(detection); + } + + auto timestamp = + std::chrono::steady_clock::time_point(std::chrono::steady_clock::duration( + dataProvider.ConsumeIntegral())); + inNetData->setTimestamp(timestamp); + + auto timestampDevice = + std::chrono::steady_clock::time_point(std::chrono::steady_clock::duration( + dataProvider.ConsumeIntegral())); + inNetData->setTimestampDevice(timestampDevice); + + inNetData->setSequenceNum(dataProvider.ConsumeIntegral()); + + std::deque opDetectionMsgs; + + detectionConverter.toRosMsg(inNetData, opDetectionMsgs); + auto rosMsgPtr = detectionConverter.toRosMsgPtr(inNetData); + + return 0; +} diff --git a/fuzz/imu_conv_fuzz.cc b/fuzz/imu_conv_fuzz.cc new file mode 100644 index 0000000..c1bdf37 --- /dev/null +++ b/fuzz/imu_conv_fuzz.cc @@ -0,0 +1,56 @@ +#include +#include + +#include "depthai-shared/common/CameraInfo.hpp" +#include +#include +#include +#include +#include +#include +#include +#include + +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(); + // NOTE: Starting from 0 leads to an OOB access + size_t numPackets = dataProvider.ConsumeIntegralInRange(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(); + packet.acceleroMeter.y = dataProvider.ConsumeFloatingPoint(); + packet.acceleroMeter.z = dataProvider.ConsumeFloatingPoint(); + + packet.gyroscope.x = dataProvider.ConsumeFloatingPoint(); + packet.gyroscope.y = dataProvider.ConsumeFloatingPoint(); + packet.gyroscope.z = dataProvider.ConsumeFloatingPoint(); + + packet.magneticField.x = dataProvider.ConsumeFloatingPoint(); + packet.magneticField.y = dataProvider.ConsumeFloatingPoint(); + packet.magneticField.z = dataProvider.ConsumeFloatingPoint(); + + packet.rotationVector.i = dataProvider.ConsumeFloatingPoint(); + packet.rotationVector.j = dataProvider.ConsumeFloatingPoint(); + packet.rotationVector.k = dataProvider.ConsumeFloatingPoint(); + packet.rotationVector.real = dataProvider.ConsumeFloatingPoint(); + packet.rotationVector.rotationVectorAccuracy = + dataProvider.ConsumeFloatingPoint(); + + 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; +}