mirror of
https://github.com/paparazzi/paparazzi.git
synced 2026-02-05 10:41:00 +08:00
Fix compilation tests (#3550)
* [fix] fix some bugs small errors from compilation tests * Attempt to fix the detection of failing tests Side effect: the file issues.md is not produced anymore, but still available in stdout, so needs a manual copy if needed
This commit is contained in:
committed by
GitHub
parent
b4ba0dac47
commit
4ac6279aa9
8
Makefile
8
Makefile
@@ -305,7 +305,7 @@ test: test_math test_examples test_modules
|
|||||||
# subset of airframes for coverity test to pass the limited build time on travis
|
# subset of airframes for coverity test to pass the limited build time on travis
|
||||||
test_coverity: all
|
test_coverity: all
|
||||||
CONF_XML=conf/conf_tests_coverity.xml prove tests/aircrafts/ 2>&1 | tee ./var/compile.log
|
CONF_XML=conf/conf_tests_coverity.xml prove tests/aircrafts/ 2>&1 | tee ./var/compile.log
|
||||||
python ./sw/tools/parse_compile_logs.py
|
prove -v ./tests/parse_compile_logs.py
|
||||||
|
|
||||||
# test AggieAir conf
|
# test AggieAir conf
|
||||||
test_aggieair: all
|
test_aggieair: all
|
||||||
@@ -323,7 +323,7 @@ test_tudelft: all
|
|||||||
CONF_XML=conf/userconf/tudelft/delfly_conf.xml prove tests/aircrafts/ 2>&1 | tee -a ./var/compile.log
|
CONF_XML=conf/userconf/tudelft/delfly_conf.xml prove tests/aircrafts/ 2>&1 | tee -a ./var/compile.log
|
||||||
CONF_XML=conf/userconf/tudelft/course_conf.xml prove tests/aircrafts/ 2>&1 | tee -a ./var/compile.log
|
CONF_XML=conf/userconf/tudelft/course_conf.xml prove tests/aircrafts/ 2>&1 | tee -a ./var/compile.log
|
||||||
CONF_XML=conf/userconf/tudelft/guido_conf.xml prove tests/aircrafts/ 2>&1 | tee -a ./var/compile.log
|
CONF_XML=conf/userconf/tudelft/guido_conf.xml prove tests/aircrafts/ 2>&1 | tee -a ./var/compile.log
|
||||||
python ./sw/tools/parse_compile_logs.py | tee ./issues.md
|
prove -v ./tests/parse_compile_logs.py
|
||||||
|
|
||||||
# test GVF conf
|
# test GVF conf
|
||||||
test_gvf: all
|
test_gvf: all
|
||||||
@@ -333,7 +333,7 @@ test_gvf: all
|
|||||||
# compiles all aircrafts in conf_tests.xml
|
# compiles all aircrafts in conf_tests.xml
|
||||||
test_examples: all
|
test_examples: all
|
||||||
CONF_XML=conf/conf_tests.xml prove tests/aircrafts/ 2>&1 | tee ./var/compile.log
|
CONF_XML=conf/conf_tests.xml prove tests/aircrafts/ 2>&1 | tee ./var/compile.log
|
||||||
python ./sw/tools/parse_compile_logs.py | tee ./issues.md
|
prove -v ./tests/parse_compile_logs.py
|
||||||
|
|
||||||
# test compilation of modules
|
# test compilation of modules
|
||||||
test_modules: all
|
test_modules: all
|
||||||
@@ -350,7 +350,7 @@ test_math:
|
|||||||
|
|
||||||
test_full:
|
test_full:
|
||||||
make -C ./ test_all_confs 2>&1 | tee ./var/compile.log
|
make -C ./ test_all_confs 2>&1 | tee ./var/compile.log
|
||||||
python ./sw/tools/parse_compile_logs.py | tee ./issues.md
|
prove -v ./tests/parse_compile_logs.py
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
@@ -17,7 +17,7 @@
|
|||||||
radio="radios/dummy.xml"
|
radio="radios/dummy.xml"
|
||||||
telemetry="telemetry/default_rotorcraft.xml"
|
telemetry="telemetry/default_rotorcraft.xml"
|
||||||
flight_plan="flight_plans/rotorcraft_survey.xml"
|
flight_plan="flight_plans/rotorcraft_survey.xml"
|
||||||
settings="settings/rotorcraft_basic.xml settings/estimation/ahrs_secondary.xml"
|
settings="settings/rotorcraft_basic.xml"
|
||||||
settings_modules="modules/ahrs_float_mlkf.xml modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/bebop_cam.xml modules/cv_blob_locator.xml modules/digital_cam_video.xml modules/geo_mag.xml modules/gps.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_extended.xml modules/nav_basic_rotorcraft.xml modules/nav_survey_poly_rotorcraft.xml modules/nav_survey_rectangle_rotorcraft.xml modules/stabilization_indi_simple.xml modules/video_capture.xml modules/video_rtp_stream.xml"
|
settings_modules="modules/ahrs_float_mlkf.xml modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/bebop_cam.xml modules/cv_blob_locator.xml modules/digital_cam_video.xml modules/geo_mag.xml modules/gps.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_extended.xml modules/nav_basic_rotorcraft.xml modules/nav_survey_poly_rotorcraft.xml modules/nav_survey_rectangle_rotorcraft.xml modules/stabilization_indi_simple.xml modules/video_capture.xml modules/video_rtp_stream.xml"
|
||||||
gui_color="#ffff0689b7a1"
|
gui_color="#ffff0689b7a1"
|
||||||
/>
|
/>
|
||||||
@@ -28,7 +28,7 @@
|
|||||||
radio="radios/dummy.xml"
|
radio="radios/dummy.xml"
|
||||||
telemetry="telemetry/default_rotorcraft.xml"
|
telemetry="telemetry/default_rotorcraft.xml"
|
||||||
flight_plan="flight_plans/tudelft/rotorcraft_survey_delft.xml"
|
flight_plan="flight_plans/tudelft/rotorcraft_survey_delft.xml"
|
||||||
settings="settings/rotorcraft_basic.xml settings/estimation/ahrs_secondary.xml"
|
settings="settings/rotorcraft_basic.xml"
|
||||||
settings_modules="modules/ahrs_float_mlkf.xml modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/bebop_cam.xml modules/cv_blob_locator.xml modules/digital_cam_video.xml modules/geo_mag.xml modules/gps.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_extended.xml modules/nav_basic_rotorcraft.xml modules/nav_survey_poly_rotorcraft.xml modules/nav_survey_rectangle_rotorcraft.xml modules/stabilization_indi_simple.xml modules/video_capture.xml modules/video_rtp_stream.xml"
|
settings_modules="modules/ahrs_float_mlkf.xml modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/bebop_cam.xml modules/cv_blob_locator.xml modules/digital_cam_video.xml modules/geo_mag.xml modules/gps.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_extended.xml modules/nav_basic_rotorcraft.xml modules/nav_survey_poly_rotorcraft.xml modules/nav_survey_rectangle_rotorcraft.xml modules/stabilization_indi_simple.xml modules/video_capture.xml modules/video_rtp_stream.xml"
|
||||||
gui_color="#ffff0689b7a1"
|
gui_color="#ffff0689b7a1"
|
||||||
/>
|
/>
|
||||||
|
|||||||
@@ -28,7 +28,7 @@
|
|||||||
radio="radios/dummy.xml"
|
radio="radios/dummy.xml"
|
||||||
telemetry="telemetry/default_rotorcraft.xml"
|
telemetry="telemetry/default_rotorcraft.xml"
|
||||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||||
settings="settings/rotorcraft_basic.xml settings/setup_actuators.xml settings/estimation/ahrs_secondary.xml"
|
settings="settings/rotorcraft_basic.xml settings/setup_actuators.xml"
|
||||||
settings_modules="modules/ahrs_float_mlkf.xml modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/electrical.xml modules/geo_mag.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_rotorcraft.xml modules/stabilization_int_quat.xml"
|
settings_modules="modules/ahrs_float_mlkf.xml modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/electrical.xml modules/geo_mag.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_rotorcraft.xml modules/stabilization_int_quat.xml"
|
||||||
gui_color="blue"
|
gui_color="blue"
|
||||||
/>
|
/>
|
||||||
|
|||||||
@@ -18,7 +18,7 @@
|
|||||||
telemetry="telemetry/default_fixedwing_imu.xml"
|
telemetry="telemetry/default_fixedwing_imu.xml"
|
||||||
flight_plan="flight_plans/versatile.xml"
|
flight_plan="flight_plans/versatile.xml"
|
||||||
settings="settings/fixedwing_basic.xml"
|
settings="settings/fixedwing_basic.xml"
|
||||||
settings_modules="modules/ahrs_float_dcm.xml modules/air_data.xml modules/digital_cam.xml modules/electrical.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/light.xml modules/nav_basic_fw.xml modules/nav_catapult.xml modules/stabilization_attitude_fw.xml"
|
settings_modules="modules/ahrs_float_dcm.xml modules/air_data.xml modules/digital_cam_common.xml modules/electrical.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/light.xml modules/nav_basic_fw.xml modules/nav_catapult.xml modules/stabilization_attitude_fw.xml"
|
||||||
gui_color="blue"
|
gui_color="blue"
|
||||||
/>
|
/>
|
||||||
<aircraft
|
<aircraft
|
||||||
@@ -62,7 +62,7 @@
|
|||||||
telemetry="telemetry/highspeed_rotorcraft.xml"
|
telemetry="telemetry/highspeed_rotorcraft.xml"
|
||||||
flight_plan="flight_plans/tudelft/rotwing_troia.xml"
|
flight_plan="flight_plans/tudelft/rotwing_troia.xml"
|
||||||
settings="settings/rotorcraft_basic.xml"
|
settings="settings/rotorcraft_basic.xml"
|
||||||
settings_modules="modules/air_data.xml modules/airspeed_ms45xx_i2c.xml modules/airspeed_uavcan.xml modules/approach_moving_target.xml modules/eff_scheduling_rotwing.xml modules/ekf_aw.xml modules/electrical.xml modules/gps.xml modules/gps_ublox.xml modules/guidance_indi_hybrid.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/imu_heater.xml modules/ins_ekf2.xml modules/logger_sd_chibios.xml modules/nav_hybrid.xml modules/nav_rotorcraft.xml modules/parachute.xml modules/pfc_actuators.xml modules/preflight_checks.xml modules/rotwing_state.xml modules/stabilization_indi.xml modules/sys_id_auto_doublets.xml modules/sys_id_doublet.xml modules/target_pos.xml"
|
settings_modules="modules/air_data.xml modules/airspeed_consistency.xml modules/airspeed_ms45xx_i2c.xml modules/airspeed_uavcan.xml modules/approach_moving_target.xml modules/eff_scheduling_rotwing.xml modules/ekf_aw.xml modules/electrical.xml modules/gps.xml modules/gps_ublox.xml modules/guidance_indi_hybrid.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/imu_heater.xml modules/ins_ekf2.xml modules/logger_sd_chibios.xml modules/nav_hybrid.xml modules/nav_rotorcraft.xml modules/parachute.xml modules/pfc_actuators.xml modules/preflight_checks.xml modules/rotwing_state.xml modules/stabilization_indi.xml modules/sys_id_auto_doublets.xml modules/sys_id_doublet.xml modules/target_pos.xml"
|
||||||
gui_color="red"
|
gui_color="red"
|
||||||
/>
|
/>
|
||||||
<aircraft
|
<aircraft
|
||||||
@@ -83,7 +83,7 @@
|
|||||||
radio="radios/dummy.xml"
|
radio="radios/dummy.xml"
|
||||||
telemetry="telemetry/default_rotorcraft_mavlink.xml"
|
telemetry="telemetry/default_rotorcraft_mavlink.xml"
|
||||||
flight_plan="flight_plans/rotorcraft_basic.xml"
|
flight_plan="flight_plans/rotorcraft_basic.xml"
|
||||||
settings="settings/rotorcraft_basic.xml settings/estimation/ahrs_secondary.xml"
|
settings="settings/rotorcraft_basic.xml"
|
||||||
settings_modules="modules/ahrs_float_mlkf.xml modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/electrical.xml modules/geo_mag.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_rotorcraft.xml modules/stabilization_int_quat.xml"
|
settings_modules="modules/ahrs_float_mlkf.xml modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/electrical.xml modules/geo_mag.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_rotorcraft.xml modules/stabilization_int_quat.xml"
|
||||||
gui_color="blue"
|
gui_color="blue"
|
||||||
/>
|
/>
|
||||||
|
|||||||
@@ -10,7 +10,7 @@
|
|||||||
<define name="USE_CANx" value="FALSE" description="Enable the CANx port"/>
|
<define name="USE_CANx" value="FALSE" description="Enable the CANx port"/>
|
||||||
</doc>
|
</doc>
|
||||||
<dep>
|
<dep>
|
||||||
<depends>mcu</depends>
|
<depends>mcu,threads</depends>
|
||||||
</dep>
|
</dep>
|
||||||
<header>
|
<header>
|
||||||
<file name="can.h" dir="mcu_periph"/>
|
<file name="can.h" dir="mcu_periph"/>
|
||||||
|
|||||||
@@ -7,6 +7,9 @@
|
|||||||
To activate a specific I2C peripheral, define flag USE_I2CX where X is your I2C peripheral number
|
To activate a specific I2C peripheral, define flag USE_I2CX where X is your I2C peripheral number
|
||||||
</description>
|
</description>
|
||||||
</doc>
|
</doc>
|
||||||
|
<dep>
|
||||||
|
<depends>mcu,threads</depends>
|
||||||
|
</dep>
|
||||||
<header>
|
<header>
|
||||||
<file name="i2c.h" dir="mcu_periph"/>
|
<file name="i2c.h" dir="mcu_periph"/>
|
||||||
</header>
|
</header>
|
||||||
|
|||||||
@@ -8,7 +8,7 @@
|
|||||||
</description>
|
</description>
|
||||||
</doc>
|
</doc>
|
||||||
<dep>
|
<dep>
|
||||||
<depends>mcu</depends>
|
<depends>mcu,threads</depends>
|
||||||
</dep>
|
</dep>
|
||||||
<header>
|
<header>
|
||||||
<file name="spi.h" dir="mcu_periph"/>
|
<file name="spi.h" dir="mcu_periph"/>
|
||||||
|
|||||||
@@ -7,6 +7,9 @@
|
|||||||
</description>
|
</description>
|
||||||
<configure name="SYS_TIME_LED" value="none|num" description="LED number used for systime heartbeat or 'none' to disable"/>
|
<configure name="SYS_TIME_LED" value="none|num" description="LED number used for systime heartbeat or 'none' to disable"/>
|
||||||
</doc>
|
</doc>
|
||||||
|
<dep>
|
||||||
|
<depends>threads</depends>
|
||||||
|
</dep>
|
||||||
<header>
|
<header>
|
||||||
<file name="sys_time.h" dir="mcu_periph"/>
|
<file name="sys_time.h" dir="mcu_periph"/>
|
||||||
</header>
|
</header>
|
||||||
|
|||||||
@@ -8,7 +8,7 @@
|
|||||||
</description>
|
</description>
|
||||||
</doc>
|
</doc>
|
||||||
<dep>
|
<dep>
|
||||||
<depends>mcu</depends>
|
<depends>mcu,threads</depends>
|
||||||
</dep>
|
</dep>
|
||||||
<header>
|
<header>
|
||||||
<file name="uart.h" dir="mcu_periph"/>
|
<file name="uart.h" dir="mcu_periph"/>
|
||||||
|
|||||||
@@ -1,11 +0,0 @@
|
|||||||
<!DOCTYPE settings SYSTEM "../settings.dtd">
|
|
||||||
|
|
||||||
<settings target="ap|nps|test_ahrs">
|
|
||||||
<dl_settings>
|
|
||||||
|
|
||||||
<dl_settings NAME="AHRS">
|
|
||||||
<dl_setting var="ahrs_output_idx" min="0" step="1" max="1" values="PRIMARY|SECONDARY" module="modules/ahrs/ahrs" shortname="ahrs output" handler="switch"/>
|
|
||||||
</dl_settings>
|
|
||||||
|
|
||||||
</dl_settings>
|
|
||||||
</settings>
|
|
||||||
@@ -28,7 +28,7 @@
|
|||||||
radio="radios/dummy.xml"
|
radio="radios/dummy.xml"
|
||||||
telemetry="telemetry/default_rotorcraft_mavlink.xml"
|
telemetry="telemetry/default_rotorcraft_mavlink.xml"
|
||||||
flight_plan="flight_plans/tudelft/rotorcraft_survey_delft.xml"
|
flight_plan="flight_plans/tudelft/rotorcraft_survey_delft.xml"
|
||||||
settings="settings/rotorcraft_basic.xml settings/estimation/ahrs_secondary.xml settings/control/rotorcraft_speed.xml"
|
settings="settings/rotorcraft_basic.xml settings/control/rotorcraft_speed.xml"
|
||||||
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/bebop_cam.xml modules/cv_blob_locator.xml modules/digital_cam_video.xml modules/geo_mag.xml modules/gps.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_extended.xml modules/nav_basic_rotorcraft.xml [modules/nav_survey_poly_rotorcraft.xml] [modules/nav_survey_rectangle_rotorcraft.xml] modules/stabilization_indi_simple.xml modules/video_capture.xml"
|
settings_modules="modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/bebop_cam.xml modules/cv_blob_locator.xml modules/digital_cam_video.xml modules/geo_mag.xml modules/gps.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_extended.xml modules/nav_basic_rotorcraft.xml [modules/nav_survey_poly_rotorcraft.xml] [modules/nav_survey_rectangle_rotorcraft.xml] modules/stabilization_indi_simple.xml modules/video_capture.xml"
|
||||||
gui_color="#ffff0689b7a1"
|
gui_color="#ffff0689b7a1"
|
||||||
/>
|
/>
|
||||||
@@ -424,7 +424,7 @@
|
|||||||
radio="radios/dummy.xml"
|
radio="radios/dummy.xml"
|
||||||
telemetry="telemetry/default_rotorcraft.xml"
|
telemetry="telemetry/default_rotorcraft.xml"
|
||||||
flight_plan="flight_plans/tudelft/delft_bebop.xml"
|
flight_plan="flight_plans/tudelft/delft_bebop.xml"
|
||||||
settings="settings/rotorcraft_basic.xml [settings/estimation/ahrs_secondary.xml]"
|
settings="settings/rotorcraft_basic.xml"
|
||||||
settings_modules="modules/air_data.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_ekf2.xml modules/nav_basic_rotorcraft.xml modules/stabilization_indi_simple.xml"
|
settings_modules="modules/air_data.xml modules/gps.xml modules/gps_ubx_ucenter.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/ins_ekf2.xml modules/nav_basic_rotorcraft.xml modules/stabilization_indi_simple.xml"
|
||||||
gui_color="#baa3d698b729"
|
gui_color="#baa3d698b729"
|
||||||
/>
|
/>
|
||||||
|
|||||||
@@ -33,7 +33,7 @@
|
|||||||
#include "std.h"
|
#include "std.h"
|
||||||
#include "math/pprz_algebra_int.h"
|
#include "math/pprz_algebra_int.h"
|
||||||
#include "math/pprz_algebra_float.h"
|
#include "math/pprz_algebra_float.h"
|
||||||
#include "filters/high_pass_filter.h"
|
#include "filters/low_pass_filter.h"
|
||||||
#include "firmwares/rotorcraft/guidance.h"
|
#include "firmwares/rotorcraft/guidance.h"
|
||||||
#include "firmwares/rotorcraft/stabilization.h"
|
#include "firmwares/rotorcraft/stabilization.h"
|
||||||
|
|
||||||
|
|||||||
@@ -25,7 +25,7 @@
|
|||||||
|
|
||||||
#include "pprz_random.h"
|
#include "pprz_random.h"
|
||||||
|
|
||||||
#ifdef BOARD_CONFIG
|
#if (defined BOARD_CONFIG) && (!defined HITL)
|
||||||
#include "mcu_periph/sys_time.h"
|
#include "mcu_periph/sys_time.h"
|
||||||
#else
|
#else
|
||||||
#include <time.h>
|
#include <time.h>
|
||||||
@@ -34,7 +34,7 @@
|
|||||||
|
|
||||||
void init_random(void)
|
void init_random(void)
|
||||||
{
|
{
|
||||||
#ifdef BOARD_CONFIG
|
#if (defined BOARD_CONFIG) && (!defined HITL)
|
||||||
srand(get_sys_time_msec());
|
srand(get_sys_time_msec());
|
||||||
#else
|
#else
|
||||||
srand(time(NULL));
|
srand(time(NULL));
|
||||||
|
|||||||
@@ -22,10 +22,10 @@
|
|||||||
|
|
||||||
#include "mcu_periph/uart.h"
|
#include "mcu_periph/uart.h"
|
||||||
|
|
||||||
#if PERIODIC_TELEMETRY && (USE_UART0 || USE_UART1 || USE_UART2 || USE_UART3 || USE_UART4 || USE_UART5 || USE_UART6 || USE_UART7 || USE_UART8)
|
#if PERIODIC_TELEMETRY
|
||||||
#include "modules/datalink/telemetry.h"
|
#include "modules/datalink/telemetry.h"
|
||||||
|
|
||||||
static void send_uartx_err(struct transport_tx *trans, struct link_device *dev, struct uart_periph* uart)
|
UNUSED static void send_uartx_err(struct transport_tx *trans, struct link_device *dev, struct uart_periph* uart)
|
||||||
{
|
{
|
||||||
uint16_t ore = uart->ore;
|
uint16_t ore = uart->ore;
|
||||||
uint16_t ne_err = uart->ne_err;
|
uint16_t ne_err = uart->ne_err;
|
||||||
|
|||||||
@@ -35,6 +35,7 @@
|
|||||||
#include "state.h"
|
#include "state.h"
|
||||||
#include "modules/gps/gps.h"
|
#include "modules/gps/gps.h"
|
||||||
#include "firmwares/fixedwing/nav.h"
|
#include "firmwares/fixedwing/nav.h"
|
||||||
|
#include "generated/modules.h"
|
||||||
|
|
||||||
|
|
||||||
#include "modules/core/abi.h"
|
#include "modules/core/abi.h"
|
||||||
|
|||||||
@@ -28,6 +28,7 @@
|
|||||||
#include "modules/ins/ins.h"
|
#include "modules/ins/ins.h"
|
||||||
|
|
||||||
#include "generated/airframe.h"
|
#include "generated/airframe.h"
|
||||||
|
#include "generated/modules.h"
|
||||||
|
|
||||||
#include "mcu_periph/sys_time.h"
|
#include "mcu_periph/sys_time.h"
|
||||||
#include "modules/core/abi.h"
|
#include "modules/core/abi.h"
|
||||||
|
|||||||
@@ -6,6 +6,10 @@
|
|||||||
import os
|
import os
|
||||||
import sys
|
import sys
|
||||||
import re
|
import re
|
||||||
|
from os import path
|
||||||
|
|
||||||
|
sys.path.append(path.normpath(path.join(path.dirname(path.abspath(__file__)), 'modules')))
|
||||||
|
from TAP import Builder
|
||||||
|
|
||||||
def parse_log(log_file):
|
def parse_log(log_file):
|
||||||
with open(log_file, 'r') as f:
|
with open(log_file, 'r') as f:
|
||||||
@@ -41,8 +45,9 @@ def parse_log(log_file):
|
|||||||
def print_errors(errors):
|
def print_errors(errors):
|
||||||
last_conf = ''
|
last_conf = ''
|
||||||
last_airframe = ''
|
last_airframe = ''
|
||||||
|
ok = Builder.create(1).ok
|
||||||
if len(errors) == 0:
|
if len(errors) == 0:
|
||||||
print(' - everything looks OK!')
|
ok(True,' - everything looks OK!')
|
||||||
return
|
return
|
||||||
for conf, airframe, error in errors:
|
for conf, airframe, error in errors:
|
||||||
if conf != last_conf:
|
if conf != last_conf:
|
||||||
@@ -56,7 +61,8 @@ def print_errors(errors):
|
|||||||
print(' - ',airframe)
|
print(' - ',airframe)
|
||||||
last_airframe = airframe
|
last_airframe = airframe
|
||||||
|
|
||||||
print('\t- [ ] ```',error, '```')
|
print('\t- [ ] ```',error,'```')
|
||||||
|
ok(False,f'- found {len(errors)} errors')
|
||||||
|
|
||||||
|
|
||||||
if __name__ == '__main__':
|
if __name__ == '__main__':
|
||||||
Reference in New Issue
Block a user