mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-24 15:40:31 +08:00
WIP posix_sitl_test
This commit is contained in:
committed by
Lorenz Meier
parent
2bc74fd5d9
commit
39d388051a
@@ -155,6 +155,9 @@ mindpx-v2_default:
|
||||
posix_sitl_default:
|
||||
$(call cmake-build,$@)
|
||||
|
||||
posix_sitl_test:
|
||||
$(call cmake-build,$@)
|
||||
|
||||
posix_sitl_lpe:
|
||||
$(call cmake-build,$@)
|
||||
|
||||
@@ -225,7 +228,7 @@ ifeq ($(VECTORCONTROL),1)
|
||||
@(rm -rf vectorcontrol && git clone --quiet --depth 1 https://github.com/thiemar/vectorcontrol.git && cd vectorcontrol && BOARD=s2740vc_1_0 make --silent --no-print-directory && BOARD=px4esc_1_6 make --silent --no-print-directory && ../Tools/uavcan_copy.sh)
|
||||
endif
|
||||
|
||||
check: check_px4fmu-v1_default check_px4fmu-v2_default check_px4fmu-v2_test check_px4fmu-v2_ekf2 check_px4fmu-v2_lpe check_px4fmu-v4_default_and_uavcan check_mindpx-v2_default check_px4-stm32f4discovery_default check_posix_sitl_default check_unittest check_format
|
||||
check: check_px4fmu-v1_default check_px4fmu-v2_default check_px4fmu-v2_test check_px4fmu-v2_ekf2 check_px4fmu-v2_lpe check_px4fmu-v4_default_and_uavcan check_mindpx-v2_default check_px4-stm32f4discovery_default check_posix_sitl_default check_posix_sitl_test check_unittest check_format
|
||||
|
||||
check_format:
|
||||
$(call colorecho,"Checking formatting with astyle")
|
||||
|
||||
@@ -3,68 +3,74 @@ include(posix/px4_impl_posix)
|
||||
set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Toolchain-native.cmake)
|
||||
|
||||
set(config_module_list
|
||||
drivers/device
|
||||
drivers/boards/sitl
|
||||
drivers/pwm_out_sim
|
||||
platforms/common
|
||||
platforms/posix/px4_layer
|
||||
platforms/posix/work_queue
|
||||
platforms/posix/drivers/adcsim
|
||||
platforms/posix/drivers/gpssim
|
||||
drivers/device
|
||||
drivers/gps
|
||||
platforms/posix/drivers/tonealrmsim
|
||||
drivers/pwm_out_sim
|
||||
|
||||
platforms/common
|
||||
platforms/posix/drivers/accelsim
|
||||
platforms/posix/drivers/adcsim
|
||||
platforms/posix/drivers/airspeedsim
|
||||
platforms/posix/drivers/barosim
|
||||
platforms/posix/drivers/gpssim
|
||||
platforms/posix/drivers/gyrosim
|
||||
platforms/posix/drivers/rgbledsim
|
||||
platforms/posix/drivers/ledsim
|
||||
systemcmds/param
|
||||
systemcmds/mixer
|
||||
systemcmds/ver
|
||||
platforms/posix/drivers/rgbledsim
|
||||
platforms/posix/drivers/tonealrmsim
|
||||
platforms/posix/px4_layer
|
||||
platforms/posix/work_queue
|
||||
|
||||
systemcmds/esc_calib
|
||||
systemcmds/mixer
|
||||
systemcmds/param
|
||||
systemcmds/perf
|
||||
systemcmds/reboot
|
||||
systemcmds/sd_bench
|
||||
systemcmds/topic_listener
|
||||
systemcmds/perf
|
||||
modules/uORB
|
||||
modules/param
|
||||
modules/systemlib
|
||||
modules/systemlib/mixer
|
||||
modules/sensors
|
||||
modules/simulator
|
||||
modules/mavlink
|
||||
systemcmds/ver
|
||||
|
||||
modules/attitude_estimator_ekf
|
||||
modules/attitude_estimator_q
|
||||
modules/commander
|
||||
modules/dataman
|
||||
modules/ekf2
|
||||
modules/ekf_att_pos_estimator
|
||||
modules/position_estimator_inav
|
||||
modules/navigator
|
||||
modules/vtol_att_control
|
||||
modules/mc_pos_control
|
||||
modules/mc_att_control
|
||||
modules/mc_pos_control_multiplatform
|
||||
modules/mc_att_control_multiplatform
|
||||
modules/land_detector
|
||||
modules/fw_att_control
|
||||
modules/fw_pos_control_l1
|
||||
modules/dataman
|
||||
modules/sdlog2
|
||||
modules/commander
|
||||
modules/land_detector
|
||||
modules/load_mon
|
||||
modules/mavlink
|
||||
modules/mc_att_control
|
||||
modules/mc_att_control_multiplatform
|
||||
modules/mc_pos_control
|
||||
|
||||
modules/mc_pos_control_multiplatform
|
||||
modules/navigator
|
||||
modules/param
|
||||
modules/position_estimator_inav
|
||||
modules/sdlog2
|
||||
modules/sensors
|
||||
modules/simulator
|
||||
modules/systemlib
|
||||
modules/systemlib/mixer
|
||||
modules/uORB
|
||||
modules/vtol_att_control
|
||||
|
||||
lib/controllib
|
||||
lib/mathlib
|
||||
lib/mathlib/math/filter
|
||||
lib/conversion
|
||||
lib/DriverFramework/framework
|
||||
lib/ecl
|
||||
lib/external_lgpl
|
||||
lib/geo
|
||||
lib/geo_lookup
|
||||
lib/launchdetection
|
||||
lib/terrain_estimation
|
||||
lib/mathlib
|
||||
lib/mathlib/math/filter
|
||||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/DriverFramework/framework
|
||||
lib/terrain_estimation
|
||||
|
||||
examples/px4_simple_app
|
||||
)
|
||||
|
||||
|
||||
@@ -0,0 +1,105 @@
|
||||
include(posix/px4_impl_posix)
|
||||
|
||||
set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Toolchain-native.cmake)
|
||||
|
||||
set(config_module_list
|
||||
drivers/boards/sitl
|
||||
drivers/device
|
||||
drivers/gps
|
||||
drivers/pwm_out_sim
|
||||
|
||||
platforms/common
|
||||
platforms/posix/drivers/accelsim
|
||||
platforms/posix/drivers/adcsim
|
||||
platforms/posix/drivers/airspeedsim
|
||||
platforms/posix/drivers/barosim
|
||||
platforms/posix/drivers/gpssim
|
||||
platforms/posix/drivers/gyrosim
|
||||
platforms/posix/drivers/ledsim
|
||||
platforms/posix/drivers/rgbledsim
|
||||
platforms/posix/drivers/tonealrmsim
|
||||
platforms/posix/px4_layer
|
||||
platforms/posix/work_queue
|
||||
|
||||
systemcmds/esc_calib
|
||||
systemcmds/mixer
|
||||
systemcmds/param
|
||||
systemcmds/perf
|
||||
systemcmds/reboot
|
||||
systemcmds/topic_listener
|
||||
systemcmds/ver
|
||||
|
||||
modules/attitude_estimator_ekf
|
||||
modules/attitude_estimator_q
|
||||
modules/commander
|
||||
modules/dataman
|
||||
modules/ekf2
|
||||
modules/ekf_att_pos_estimator
|
||||
modules/fw_att_control
|
||||
modules/fw_pos_control_l1
|
||||
modules/land_detector
|
||||
modules/mavlink
|
||||
modules/mc_att_control
|
||||
modules/mc_att_control_multiplatform
|
||||
modules/mc_pos_control
|
||||
modules/mc_pos_control_multiplatform
|
||||
modules/navigator
|
||||
modules/param
|
||||
modules/position_estimator_inav
|
||||
modules/sdlog2
|
||||
modules/sensors
|
||||
modules/simulator
|
||||
modules/systemlib
|
||||
modules/systemlib/mixer
|
||||
modules/uORB
|
||||
modules/vtol_att_control
|
||||
|
||||
lib/controllib
|
||||
lib/conversion
|
||||
lib/ecl
|
||||
lib/external_lgpl
|
||||
lib/geo
|
||||
lib/geo_lookup
|
||||
lib/launchdetection
|
||||
lib/mathlib
|
||||
lib/mathlib/math/filter
|
||||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/terrain_estimation
|
||||
|
||||
examples/px4_simple_app
|
||||
|
||||
#
|
||||
# Testing
|
||||
#
|
||||
modules/commander/commander_tests
|
||||
modules/controllib_test
|
||||
#modules/mavlink/mavlink_tests
|
||||
modules/unit_test
|
||||
systemcmds/tests
|
||||
|
||||
)
|
||||
|
||||
set(config_extra_builtin_cmds
|
||||
serdis
|
||||
sercon
|
||||
)
|
||||
|
||||
set(config_sitl_rcS
|
||||
posix-configs/SITL/init/rcS
|
||||
CACHE FILEPATH "init script for sitl"
|
||||
)
|
||||
|
||||
set(config_sitl_viewer
|
||||
jmavsim
|
||||
CACHE STRING "viewer for sitl"
|
||||
)
|
||||
set_property(CACHE config_sitl_viewer
|
||||
PROPERTY STRINGS "jmavsim;none")
|
||||
|
||||
set(config_sitl_debugger
|
||||
disable
|
||||
CACHE STRING "debugger for sitl"
|
||||
)
|
||||
set_property(CACHE config_sitl_debugger
|
||||
PROPERTY STRINGS "disable;gdb;lldb")
|
||||
@@ -0,0 +1,61 @@
|
||||
uorb start
|
||||
simulator start -s
|
||||
param load
|
||||
param set MAV_TYPE 2
|
||||
param set MC_PITCHRATE_P 0.15
|
||||
param set MC_PITCH_P 7
|
||||
param set MC_ROLL_P 7
|
||||
param set MC_ROLLRATE_P 0.15
|
||||
param set MC_YAW_P 2.8
|
||||
param set MC_YAWRATE_P 0.35
|
||||
param set SYS_AUTOSTART 4010
|
||||
param set SYS_RESTART_TYPE 2
|
||||
dataman start
|
||||
param set CAL_GYRO0_ID 2293768
|
||||
param set CAL_ACC0_ID 1376264
|
||||
param set CAL_ACC1_ID 1310728
|
||||
param set CAL_MAG0_ID 196616
|
||||
param set CAL_GYRO0_XOFF 0.01
|
||||
param set CAL_ACC0_XOFF 0.01
|
||||
param set CAL_ACC0_YOFF -0.01
|
||||
param set CAL_ACC0_ZOFF 0.01
|
||||
param set CAL_ACC0_XSCALE 1.01
|
||||
param set CAL_ACC0_YSCALE 1.01
|
||||
param set CAL_ACC0_ZSCALE 1.01
|
||||
param set CAL_ACC1_XOFF 0.01
|
||||
param set CAL_MAG0_XOFF 0.01
|
||||
param set MPC_XY_P 0.4
|
||||
param set MPC_XY_VEL_P 0.2
|
||||
param set MPC_XY_VEL_D 0.005
|
||||
param set SENS_BOARD_ROT 0
|
||||
param set SENS_BOARD_X_OFF 0.000001
|
||||
param set COM_RC_IN_MODE 1
|
||||
param set COM_DL_LOSS_EN 1
|
||||
param set COM_DISARM_LAND 3
|
||||
param set NAV_ACC_RAD 2.0
|
||||
param set RTL_RETURN_ALT 30.0
|
||||
param set RTL_DESCEND_ALT 10.0
|
||||
param set RTL_LAND_DELAY 0
|
||||
param set MIS_TAKEOFF_ALT 2.5
|
||||
param set MPC_HOLD_MAX_Z 2.0
|
||||
param set MPC_HOLD_XY_DZ 0.1
|
||||
param set MPC_HOLD_Z_DZ 0.1
|
||||
param set MPC_Z_VEL_MAX 2.0
|
||||
param set MPC_Z_VEL_P 0.4
|
||||
rgbledsim start
|
||||
tone_alarm start
|
||||
gyrosim start
|
||||
accelsim start
|
||||
barosim start
|
||||
adcsim start
|
||||
gpssim start
|
||||
pwm_out_sim mode_pwm
|
||||
sleep 1
|
||||
sensors start
|
||||
|
||||
commander_tests
|
||||
controllib_test
|
||||
uorb test
|
||||
tests all
|
||||
|
||||
ver all
|
||||
@@ -638,7 +638,7 @@ bool MavlinkFtpTest::_removedirectory_test(void)
|
||||
};
|
||||
|
||||
ut_compare("mkdir failed", ::mkdir(_unittest_microsd_dir, S_IRWXU | S_IRWXG | S_IRWXO), 0);
|
||||
ut_assert("open failed", (fd = ::open(_unittest_microsd_file, O_CREAT | O_EXCL)) != -1);
|
||||
ut_assert("open failed", (fd = ::open(_unittest_microsd_file, O_CREAT | O_EXCL, S_IRWXU | S_IRWXG | S_IRWXO)) != -1);
|
||||
::close(fd);
|
||||
|
||||
for (size_t i = 0; i < sizeof(rgTestCases) / sizeof(rgTestCases[0]); i++) {
|
||||
@@ -738,7 +738,7 @@ bool MavlinkFtpTest::_removefile_test(void)
|
||||
};
|
||||
|
||||
ut_compare("mkdir failed", ::mkdir(_unittest_microsd_dir, S_IRWXU | S_IRWXG | S_IRWXO), 0);
|
||||
ut_assert("open failed", (fd = ::open(_unittest_microsd_file, O_CREAT | O_EXCL)) != -1);
|
||||
ut_assert("open failed", (fd = ::open(_unittest_microsd_file, O_CREAT | O_EXCL, S_IRWXU | S_IRWXG | S_IRWXO)) != -1);
|
||||
::close(fd);
|
||||
|
||||
for (size_t i = 0; i < sizeof(rgTestCases) / sizeof(rgTestCases[0]); i++) {
|
||||
|
||||
@@ -50,7 +50,13 @@ UnitTest::~UnitTest()
|
||||
|
||||
void UnitTest::print_results(void)
|
||||
{
|
||||
warnx(_tests_failed ? "SOME TESTS FAILED" : "ALL TESTS PASSED");
|
||||
if (_tests_failed) {
|
||||
warnx("SOME TESTS FAILED");
|
||||
|
||||
} else {
|
||||
warnx("ALL TESTS PASSED");
|
||||
}
|
||||
|
||||
warnx(" Tests passed : %d", _tests_passed);
|
||||
warnx(" Tests failed : %d", _tests_failed);
|
||||
warnx(" Assertions : %d", _assertions);
|
||||
|
||||
@@ -38,6 +38,7 @@
|
||||
****************************************************************************/
|
||||
|
||||
#include <px4_config.h>
|
||||
#include <px4_tasks.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
|
||||
|
||||
Reference in New Issue
Block a user