forked from Archive/PX4-Autopilot
posix: add fuzz testing using MAVLink messages
This adds the env option PX4_FUZZ which runs the LLVM libFuzzer which throws random bytes at mavlink_receiver using MAVLink messages over UDP. The MAVLink messages that are being sent are valid, so the CRC is calculated but the payload and msgid, etc. are generally garbage, unless the fuzzing gets a msgid right by chance. As I understand it, libFuzzer watches the test coverage and will try to execute as much of the code as possible.
This commit is contained in:
parent
c17a9e8003
commit
9eda5b373c
7
Makefile
7
Makefile
|
@ -158,6 +158,13 @@ else
|
||||||
CMAKE_ARGS += -DCMAKE_BUILD_TYPE=UndefinedBehaviorSanitizer
|
CMAKE_ARGS += -DCMAKE_BUILD_TYPE=UndefinedBehaviorSanitizer
|
||||||
endif
|
endif
|
||||||
|
|
||||||
|
# Fuzz Testing
|
||||||
|
ifdef PX4_FUZZ
|
||||||
|
export CC=clang
|
||||||
|
export CXX=clang++
|
||||||
|
CMAKE_ARGS += -DCMAKE_BUILD_TYPE=FuzzTesting
|
||||||
|
endif
|
||||||
|
|
||||||
endif
|
endif
|
||||||
|
|
||||||
# Pick up specific Python path if set
|
# Pick up specific Python path if set
|
||||||
|
|
|
@ -13,6 +13,8 @@ if(REPLAY_FILE)
|
||||||
|
|
||||||
message(STATUS "Building without lockstep for replay")
|
message(STATUS "Building without lockstep for replay")
|
||||||
set(ENABLE_LOCKSTEP_SCHEDULER no)
|
set(ENABLE_LOCKSTEP_SCHEDULER no)
|
||||||
|
elif(CMAKE_BUILD_TYPE STREQUAL FuzzTesting)
|
||||||
|
set(ENABLE_LOCKSTEP_SCHEDULER no)
|
||||||
else()
|
else()
|
||||||
set(ENABLE_LOCKSTEP_SCHEDULER yes)
|
set(ENABLE_LOCKSTEP_SCHEDULER yes)
|
||||||
endif()
|
endif()
|
||||||
|
|
|
@ -130,6 +130,23 @@ elseif (CMAKE_BUILD_TYPE STREQUAL UndefinedBehaviorSanitizer)
|
||||||
function(sanitizer_fail_test_on_error test_name)
|
function(sanitizer_fail_test_on_error test_name)
|
||||||
set_tests_properties(${test_name} PROPERTIES FAIL_REGULAR_EXPRESSION "runtime error:")
|
set_tests_properties(${test_name} PROPERTIES FAIL_REGULAR_EXPRESSION "runtime error:")
|
||||||
endfunction(sanitizer_fail_test_on_error)
|
endfunction(sanitizer_fail_test_on_error)
|
||||||
|
|
||||||
|
elseif (CMAKE_BUILD_TYPE STREQUAL FuzzTesting)
|
||||||
|
message(STATUS "FuzzTesting enabled")
|
||||||
|
|
||||||
|
add_compile_options(
|
||||||
|
-g3
|
||||||
|
-fsanitize=fuzzer,address,undefined
|
||||||
|
-DFUZZTESTING
|
||||||
|
)
|
||||||
|
|
||||||
|
set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} -fsanitize=fuzzer,address,undefined" CACHE INTERNAL "" FORCE)
|
||||||
|
set(CMAKE_SHARED_LINKER_FLAGS "${CMAKE_SHARED_LINKER_FLAGS} -fsanitize=fuzzer,address,undefined" CACHE INTERNAL "" FORCE)
|
||||||
|
set(CMAKE_MODULE_LINKER_FLAGS "${CMAKE_MODULE_LINKER_FLAGS} -fsanitize=fuzzer,address,undefined" CACHE INTERNAL "" FORCE)
|
||||||
|
|
||||||
|
function(sanitizer_fail_test_on_error test_name)
|
||||||
|
# Not sure what to do here
|
||||||
|
endfunction(sanitizer_fail_test_on_error)
|
||||||
else()
|
else()
|
||||||
|
|
||||||
function(sanitizer_fail_test_on_error test_name)
|
function(sanitizer_fail_test_on_error test_name)
|
||||||
|
|
|
@ -25,10 +25,17 @@ px4_posix_generate_alias(
|
||||||
PREFIX ${PX4_SHELL_COMMAND_PREFIX}
|
PREFIX ${PX4_SHELL_COMMAND_PREFIX}
|
||||||
)
|
)
|
||||||
|
|
||||||
add_executable(px4
|
if (CMAKE_BUILD_TYPE STREQUAL FuzzTesting)
|
||||||
src/px4/common/main.cpp
|
add_executable(px4
|
||||||
apps.cpp
|
src/px4/common/main_fuzztesting.cpp
|
||||||
)
|
apps.cpp
|
||||||
|
)
|
||||||
|
else()
|
||||||
|
add_executable(px4
|
||||||
|
src/px4/common/main.cpp
|
||||||
|
apps.cpp
|
||||||
|
)
|
||||||
|
endif()
|
||||||
|
|
||||||
target_link_libraries(px4
|
target_link_libraries(px4
|
||||||
PRIVATE
|
PRIVATE
|
||||||
|
@ -51,6 +58,11 @@ endif()
|
||||||
|
|
||||||
target_link_libraries(px4 PRIVATE uORB)
|
target_link_libraries(px4 PRIVATE uORB)
|
||||||
|
|
||||||
|
if (CMAKE_BUILD_TYPE STREQUAL FuzzTesting)
|
||||||
|
target_include_directories(px4 PRIVATE SYSTEM "${CMAKE_BINARY_DIR}/mavlink}")
|
||||||
|
target_compile_options(px4 PRIVATE "-Wno-cast-align")
|
||||||
|
endif()
|
||||||
|
|
||||||
#=============================================================================
|
#=============================================================================
|
||||||
# install
|
# install
|
||||||
#
|
#
|
||||||
|
|
|
@ -0,0 +1,158 @@
|
||||||
|
/****************************************************************************
|
||||||
|
*
|
||||||
|
* Copyright (C) 2022 PX4 Development Team. All rights reserved.
|
||||||
|
*
|
||||||
|
* Redistribution and use in source and binary forms, with or without
|
||||||
|
* modification, are permitted provided that the following conditions
|
||||||
|
* are met:
|
||||||
|
*
|
||||||
|
* 1. Redistributions of source code must retain the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer.
|
||||||
|
* 2. Redistributions in binary form must reproduce the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer in
|
||||||
|
* the documentation and/or other materials provided with the
|
||||||
|
* distribution.
|
||||||
|
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||||
|
* used to endorse or promote products derived from this software
|
||||||
|
* without specific prior written permission.
|
||||||
|
*
|
||||||
|
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||||
|
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||||
|
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||||
|
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||||
|
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||||
|
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||||
|
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||||
|
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||||
|
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||||
|
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||||
|
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||||
|
* POSSIBILITY OF SUCH DAMAGE.
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* This is an alternative main entrypoint for fuzz testing.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
|
||||||
|
#include "px4_platform_common/init.h"
|
||||||
|
#include "px4_platform_common/posix.h"
|
||||||
|
#include "apps.h"
|
||||||
|
#include "px4_daemon/client.h"
|
||||||
|
#include "px4_daemon/server.h"
|
||||||
|
#include "px4_daemon/pxh.h"
|
||||||
|
|
||||||
|
#include <netinet/in.h>
|
||||||
|
#include <arpa/inet.h>
|
||||||
|
#include "common/mavlink.h"
|
||||||
|
|
||||||
|
#define MODULE_NAME "px4"
|
||||||
|
|
||||||
|
#ifndef PATH_MAX
|
||||||
|
#define PATH_MAX 1024
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
namespace px4
|
||||||
|
{
|
||||||
|
void init_once();
|
||||||
|
}
|
||||||
|
|
||||||
|
extern "C" int LLVMFuzzerTestOneInput(const uint8_t *data, const size_t size);
|
||||||
|
void initialize_fake_px4_once();
|
||||||
|
void send_mavlink(const uint8_t *data, const size_t size);
|
||||||
|
|
||||||
|
|
||||||
|
extern "C" int LLVMFuzzerTestOneInput(const uint8_t *data, const size_t size)
|
||||||
|
{
|
||||||
|
initialize_fake_px4_once();
|
||||||
|
|
||||||
|
send_mavlink(data, size);
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
void initialize_fake_px4_once()
|
||||||
|
{
|
||||||
|
static bool first_time = true;
|
||||||
|
|
||||||
|
if (!first_time) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
first_time = false;
|
||||||
|
|
||||||
|
px4::init_once();
|
||||||
|
px4::init(0, nullptr, "px4");
|
||||||
|
|
||||||
|
px4_daemon::Pxh pxh;
|
||||||
|
pxh.process_line("uorb start", true);
|
||||||
|
pxh.process_line("param load", true);
|
||||||
|
pxh.process_line("dataman start", true);
|
||||||
|
pxh.process_line("load_mon start", true);
|
||||||
|
pxh.process_line("battery_simulator start", true);
|
||||||
|
pxh.process_line("tone_alarm start", true);
|
||||||
|
pxh.process_line("rc_update start", true);
|
||||||
|
pxh.process_line("sensors start", true);
|
||||||
|
pxh.process_line("commander start", true);
|
||||||
|
pxh.process_line("navigator start", true);
|
||||||
|
pxh.process_line("ekf2 start", true);
|
||||||
|
pxh.process_line("mc_att_control start", true);
|
||||||
|
pxh.process_line("mc_pos_control start", true);
|
||||||
|
pxh.process_line("land_detector start multicopter", true);
|
||||||
|
pxh.process_line("logger start", true);
|
||||||
|
pxh.process_line("mavlink start -x -o 14540 -r 4000000", true);
|
||||||
|
pxh.process_line("mavlink boot_complete", true);
|
||||||
|
}
|
||||||
|
|
||||||
|
void send_mavlink(const uint8_t *data, const size_t size)
|
||||||
|
{
|
||||||
|
int socket_fd = socket(AF_INET, SOCK_DGRAM, 0);
|
||||||
|
|
||||||
|
if (socket_fd < 0) {
|
||||||
|
PX4_ERR("socket error: %s", strerror(errno));
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
struct sockaddr_in addr {};
|
||||||
|
|
||||||
|
addr.sin_family = AF_INET;
|
||||||
|
|
||||||
|
inet_pton(AF_INET, "0.0.0.0", &(addr.sin_addr));
|
||||||
|
|
||||||
|
addr.sin_port = htons(14540);
|
||||||
|
|
||||||
|
if (bind(socket_fd, reinterpret_cast<sockaddr *>(&addr), sizeof(addr)) != 0) {
|
||||||
|
PX4_ERR("bind error: %s", strerror(errno));
|
||||||
|
close(socket_fd);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
mavlink_message_t message {};
|
||||||
|
uint8_t buffer[MAVLINK_MAX_PACKET_LEN] {};
|
||||||
|
|
||||||
|
for (size_t i = 0; i < size; i += sizeof(message)) {
|
||||||
|
|
||||||
|
const size_t copy_len = std::min(sizeof(message), size - i);
|
||||||
|
//printf("copy_len: %zu, %zu (%zu)\n", i, copy_len, size);
|
||||||
|
memcpy(reinterpret_cast<void *>(&message), data + i, copy_len);
|
||||||
|
|
||||||
|
const ssize_t buffer_len = mavlink_msg_to_send_buffer(buffer, &message);
|
||||||
|
|
||||||
|
struct sockaddr_in dest_addr {};
|
||||||
|
dest_addr.sin_family = AF_INET;
|
||||||
|
|
||||||
|
inet_pton(AF_INET, "127.0.0.1", &dest_addr.sin_addr.s_addr);
|
||||||
|
dest_addr.sin_port = htons(14556);
|
||||||
|
|
||||||
|
if (sendto(socket_fd, buffer, buffer_len, 0, reinterpret_cast<sockaddr *>(&dest_addr),
|
||||||
|
sizeof(dest_addr)) != buffer_len) {
|
||||||
|
PX4_ERR("sendto error: %s", strerror(errno));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
close(socket_fd);
|
||||||
|
}
|
Loading…
Reference in New Issue