forked from Archive/PX4-Autopilot
add simple posix tests to SITL
This commit is contained in:
parent
5eb3e695bb
commit
af9690cf08
16
Makefile
16
Makefile
|
@ -182,7 +182,9 @@ excelsior_legacy_default: posix_excelsior_legacy qurt_excelsior_legacy
|
||||||
# Other targets
|
# Other targets
|
||||||
# --------------------------------------------------------------------
|
# --------------------------------------------------------------------
|
||||||
|
|
||||||
.PHONY: qgc_firmware px4fmu_firmware misc_qgc_extra_firmware alt_firmware checks_bootloaders sizes check quick_check
|
.PHONY: qgc_firmware px4fmu_firmware misc_qgc_extra_firmware alt_firmware
|
||||||
|
.PHONY: sizes check quick_check check_format tests
|
||||||
|
.PHONY: check_posix_sitl_default check_px4fmu-v3_default
|
||||||
|
|
||||||
# QGroundControl flashable NuttX firmware
|
# QGroundControl flashable NuttX firmware
|
||||||
qgc_firmware: px4fmu_firmware misc_qgc_extra_firmware sizes
|
qgc_firmware: px4fmu_firmware misc_qgc_extra_firmware sizes
|
||||||
|
@ -241,7 +243,7 @@ check_%:
|
||||||
|
|
||||||
# Documentation
|
# Documentation
|
||||||
# --------------------------------------------------------------------
|
# --------------------------------------------------------------------
|
||||||
.PHONY: parameters_metadata airframe_metadata px4_metadata module_documentation
|
.PHONY: parameters_metadata airframe_metadata module_documentation px4_metadata
|
||||||
|
|
||||||
parameters_metadata: posix_sitl_default
|
parameters_metadata: posix_sitl_default
|
||||||
@python $(SRC_DIR)/Tools/px_process_params.py -s $(SRC_DIR)/src --markdown
|
@python $(SRC_DIR)/Tools/px_process_params.py -s $(SRC_DIR)/src --markdown
|
||||||
|
@ -308,13 +310,11 @@ format:
|
||||||
|
|
||||||
# Testing
|
# Testing
|
||||||
# --------------------------------------------------------------------
|
# --------------------------------------------------------------------
|
||||||
.PHONY: run_tests_posix tests tests_coverage
|
.PHONY: tests tests_coverage coveralls_upload codecov_upload
|
||||||
|
|
||||||
run_tests_posix:
|
tests:
|
||||||
$(MAKE) --no-print-directory posix_sitl_default test_results
|
$(MAKE) --no-print-directory posix_sitl_default test_results
|
||||||
|
|
||||||
tests: run_tests_posix
|
|
||||||
|
|
||||||
tests_coverage:
|
tests_coverage:
|
||||||
@$(MAKE) --no-print-directory posix_sitl_default test_coverage_genhtml PX4_CMAKE_BUILD_TYPE=Coverage
|
@$(MAKE) --no-print-directory posix_sitl_default test_coverage_genhtml PX4_CMAKE_BUILD_TYPE=Coverage
|
||||||
|
|
||||||
|
@ -331,7 +331,7 @@ codecov_upload:
|
||||||
|
|
||||||
# static analyzers (scan-build, clang-tidy, cppcheck)
|
# static analyzers (scan-build, clang-tidy, cppcheck)
|
||||||
# --------------------------------------------------------------------
|
# --------------------------------------------------------------------
|
||||||
.PHONY: posix_sitl_default-clang scan-build clang-tidy clang-tidy-fix clang-tidy-quiet cppcheck
|
.PHONY: posix_sitl_default-clang scan-build clang-tidy clang-tidy-fix clang-tidy-quiet cppcheck check_stack
|
||||||
|
|
||||||
posix_sitl_default-clang:
|
posix_sitl_default-clang:
|
||||||
@mkdir -p $(SRC_DIR)/build_posix_sitl_default-clang
|
@mkdir -p $(SRC_DIR)/build_posix_sitl_default-clang
|
||||||
|
@ -379,7 +379,7 @@ check_stack: px4fmu-v3_default
|
||||||
|
|
||||||
# Cleanup
|
# Cleanup
|
||||||
# --------------------------------------------------------------------
|
# --------------------------------------------------------------------
|
||||||
.PHONY: clean submodulesclean distclean
|
.PHONY: clean submodulesclean submodulesupdate gazeboclean distclean
|
||||||
|
|
||||||
clean:
|
clean:
|
||||||
@rm -rf $(SRC_DIR)/build_*/
|
@rm -rf $(SRC_DIR)/build_*/
|
||||||
|
|
|
@ -60,6 +60,12 @@ set(config_module_list
|
||||||
modules/uORB/uORB_tests
|
modules/uORB/uORB_tests
|
||||||
systemcmds/tests
|
systemcmds/tests
|
||||||
|
|
||||||
|
platforms/posix/tests/hello
|
||||||
|
platforms/posix/tests/hrt_test
|
||||||
|
platforms/posix/tests/muorb
|
||||||
|
platforms/posix/tests/vcdev_test
|
||||||
|
platforms/posix/tests/wqueue
|
||||||
|
|
||||||
#
|
#
|
||||||
# General system control
|
# General system control
|
||||||
#
|
#
|
||||||
|
|
|
@ -0,0 +1,37 @@
|
||||||
|
uorb start
|
||||||
|
|
||||||
|
param load
|
||||||
|
param set SYS_RESTART_TYPE 0
|
||||||
|
|
||||||
|
dataman start
|
||||||
|
|
||||||
|
simulator start -t
|
||||||
|
tone_alarm start
|
||||||
|
gyrosim start
|
||||||
|
accelsim start
|
||||||
|
barosim start
|
||||||
|
adcsim start
|
||||||
|
gpssim start
|
||||||
|
measairspeedsim start
|
||||||
|
pwm_out_sim mode_pwm
|
||||||
|
|
||||||
|
ver all
|
||||||
|
|
||||||
|
list_tasks
|
||||||
|
list_devices
|
||||||
|
list_topics
|
||||||
|
list_files
|
||||||
|
|
||||||
|
mavlink start -x -u 14556 -r 2000000
|
||||||
|
mavlink boot_complete
|
||||||
|
|
||||||
|
@cmd_name@ start
|
||||||
|
sleep 1
|
||||||
|
@cmd_name@ start
|
||||||
|
sleep 1
|
||||||
|
@cmd_name@ stop
|
||||||
|
|
||||||
|
dataman status
|
||||||
|
dataman stop
|
||||||
|
|
||||||
|
shutdown
|
|
@ -15,8 +15,6 @@ gpssim start
|
||||||
measairspeedsim start
|
measairspeedsim start
|
||||||
pwm_out_sim mode_pwm
|
pwm_out_sim mode_pwm
|
||||||
|
|
||||||
help
|
|
||||||
|
|
||||||
ver all
|
ver all
|
||||||
|
|
||||||
list_tasks
|
list_tasks
|
|
@ -40,7 +40,7 @@ if (${CMAKE_SYSTEM_NAME} MATCHES "Darwin")
|
||||||
endif()
|
endif()
|
||||||
|
|
||||||
foreach(test_name ${tests})
|
foreach(test_name ${tests})
|
||||||
configure_file(${PX4_SOURCE_DIR}/posix-configs/SITL/init/test/test_template.in ${PX4_SOURCE_DIR}/posix-configs/SITL/init/test/test_${test_name}_generated)
|
configure_file(${PX4_SOURCE_DIR}/posix-configs/SITL/init/test/tests_template.in ${PX4_SOURCE_DIR}/posix-configs/SITL/init/test/tests_${test_name}_generated)
|
||||||
|
|
||||||
add_test(NAME ${test_name}
|
add_test(NAME ${test_name}
|
||||||
COMMAND ${PX4_SOURCE_DIR}/Tools/sitl_run.sh
|
COMMAND ${PX4_SOURCE_DIR}/Tools/sitl_run.sh
|
||||||
|
@ -48,7 +48,7 @@ foreach(test_name ${tests})
|
||||||
posix-configs/SITL/init/test
|
posix-configs/SITL/init/test
|
||||||
none
|
none
|
||||||
none
|
none
|
||||||
test_${test_name}_generated
|
tests_${test_name}_generated
|
||||||
${PX4_SOURCE_DIR}
|
${PX4_SOURCE_DIR}
|
||||||
${PX4_BINARY_DIR}
|
${PX4_BINARY_DIR}
|
||||||
WORKING_DIRECTORY ${SITL_WORKING_DIR})
|
WORKING_DIRECTORY ${SITL_WORKING_DIR})
|
||||||
|
@ -57,6 +57,33 @@ foreach(test_name ${tests})
|
||||||
set_tests_properties(${test_name} PROPERTIES PASS_REGULAR_EXPRESSION "${test_name} PASSED")
|
set_tests_properties(${test_name} PROPERTIES PASS_REGULAR_EXPRESSION "${test_name} PASSED")
|
||||||
endforeach()
|
endforeach()
|
||||||
|
|
||||||
|
# run arbitrary commands
|
||||||
|
set(test_cmds
|
||||||
|
hello
|
||||||
|
hrt_test
|
||||||
|
muorb_test
|
||||||
|
vcdev_test
|
||||||
|
wqueue_test
|
||||||
|
)
|
||||||
|
|
||||||
|
foreach(cmd_name ${test_cmds})
|
||||||
|
configure_file(${PX4_SOURCE_DIR}/posix-configs/SITL/init/test/cmd_template.in ${PX4_SOURCE_DIR}/posix-configs/SITL/init/test/cmd_${cmd_name}_generated)
|
||||||
|
|
||||||
|
add_test(NAME posix_${cmd_name}
|
||||||
|
COMMAND ${PX4_SOURCE_DIR}/Tools/sitl_run.sh
|
||||||
|
$<TARGET_FILE:px4>
|
||||||
|
posix-configs/SITL/init/test
|
||||||
|
none
|
||||||
|
none
|
||||||
|
cmd_${cmd_name}_generated
|
||||||
|
${PX4_SOURCE_DIR}
|
||||||
|
${PX4_BINARY_DIR}
|
||||||
|
WORKING_DIRECTORY ${SITL_WORKING_DIR})
|
||||||
|
|
||||||
|
set_tests_properties(posix_${cmd_name} PROPERTIES PASS_REGULAR_EXPRESSION "Shutting down")
|
||||||
|
endforeach()
|
||||||
|
|
||||||
|
|
||||||
add_custom_target(test_results
|
add_custom_target(test_results
|
||||||
COMMAND ${CMAKE_CTEST_COMMAND} --output-on-failure -T Test
|
COMMAND ${CMAKE_CTEST_COMMAND} --output-on-failure -T Test
|
||||||
DEPENDS px4
|
DEPENDS px4
|
||||||
|
|
|
@ -38,6 +38,8 @@
|
||||||
* @author Mark Charlebois <mcharleb@gmail.com>
|
* @author Mark Charlebois <mcharleb@gmail.com>
|
||||||
*/
|
*/
|
||||||
#include "hello_example.h"
|
#include "hello_example.h"
|
||||||
|
|
||||||
|
#include <px4_log.h>
|
||||||
#include <px4_app.h>
|
#include <px4_app.h>
|
||||||
#include <px4_tasks.h>
|
#include <px4_tasks.h>
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
|
@ -46,7 +48,7 @@
|
||||||
|
|
||||||
#define SCHED_DEFAULT SCHED_FIFO
|
#define SCHED_DEFAULT SCHED_FIFO
|
||||||
#define SCHED_PRIORITY_MAX sched_get_priority_max(SCHED_FIFO)
|
#define SCHED_PRIORITY_MAX sched_get_priority_max(SCHED_FIFO)
|
||||||
#define SCHED_PRIORITY_DEFAULT sched_get_priority_max(SCHED_FIFO)
|
//#define SCHED_PRIORITY_DEFAULT sched_get_priority_max(SCHED_FIFO)
|
||||||
|
|
||||||
static int daemon_task; /* Handle of deamon task / thread */
|
static int daemon_task; /* Handle of deamon task / thread */
|
||||||
|
|
||||||
|
@ -74,7 +76,7 @@ int hello_main(int argc, char *argv[])
|
||||||
SCHED_PRIORITY_MAX - 5,
|
SCHED_PRIORITY_MAX - 5,
|
||||||
2000,
|
2000,
|
||||||
PX4_MAIN,
|
PX4_MAIN,
|
||||||
(argv) ? (char *const *)&argv[2] : (char *const *)NULL);
|
(argv) ? (char *const *)&argv[2] : (char *const *)nullptr);
|
||||||
|
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
|
@ -32,7 +32,7 @@
|
||||||
############################################################################
|
############################################################################
|
||||||
px4_add_module(
|
px4_add_module(
|
||||||
MODULE platforms__posix__tests__hrt_test
|
MODULE platforms__posix__tests__hrt_test
|
||||||
MAIN hrttest
|
MAIN hrt_test
|
||||||
SRCS
|
SRCS
|
||||||
hrt_test_main.cpp
|
hrt_test_main.cpp
|
||||||
hrt_test_start_posix.cpp
|
hrt_test_start_posix.cpp
|
||||||
|
|
|
@ -59,7 +59,7 @@ static void timer_expired(void *arg)
|
||||||
|
|
||||||
if (i < 5) {
|
if (i < 5) {
|
||||||
i++;
|
i++;
|
||||||
hrt_call_after(&t1, update_interval, timer_expired, (void *)0);
|
hrt_call_after(&t1, update_interval, timer_expired, (void *)nullptr);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -83,7 +83,7 @@ int HRTTest::main()
|
||||||
|
|
||||||
PX4_INFO("HRT_CALL %d\n", hrt_called(&t1));
|
PX4_INFO("HRT_CALL %d\n", hrt_called(&t1));
|
||||||
|
|
||||||
hrt_call_after(&t1, update_interval, timer_expired, (void *)0);
|
hrt_call_after(&t1, update_interval, timer_expired, (void *)nullptr);
|
||||||
sleep(2);
|
sleep(2);
|
||||||
PX4_INFO("HRT_CALL - %d\n", hrt_called(&t1));
|
PX4_INFO("HRT_CALL - %d\n", hrt_called(&t1));
|
||||||
hrt_cancel(&t1);
|
hrt_cancel(&t1);
|
||||||
|
|
|
@ -46,11 +46,11 @@
|
||||||
|
|
||||||
static int daemon_task; /* Handle of deamon task / thread */
|
static int daemon_task; /* Handle of deamon task / thread */
|
||||||
|
|
||||||
extern "C" __EXPORT int hrttest_main(int argc, char *argv[]);
|
extern "C" __EXPORT int hrt_test_main(int argc, char *argv[]);
|
||||||
int hrttest_main(int argc, char *argv[])
|
int hrt_test_main(int argc, char *argv[])
|
||||||
{
|
{
|
||||||
if (argc < 2) {
|
if (argc < 2) {
|
||||||
PX4_WARN("usage: hrttest_main {start|stop|status}\n");
|
PX4_WARN("usage: hrt_test_main {start|stop|status}\n");
|
||||||
return 1;
|
return 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -67,7 +67,7 @@ int hrttest_main(int argc, char *argv[])
|
||||||
SCHED_PRIORITY_MAX - 5,
|
SCHED_PRIORITY_MAX - 5,
|
||||||
2000,
|
2000,
|
||||||
PX4_MAIN,
|
PX4_MAIN,
|
||||||
(argv) ? (char *const *)&argv[2] : (char *const *)NULL);
|
(argv) ? (char *const *)&argv[2] : (char *const *)nullptr);
|
||||||
|
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
|
@ -60,14 +60,14 @@ int MuorbTestExample::DefaultTest()
|
||||||
int i = 0;
|
int i = 0;
|
||||||
orb_advert_t pub_id = orb_advertise(ORB_ID(esc_status), & m_esc_status);
|
orb_advert_t pub_id = orb_advertise(ORB_ID(esc_status), & m_esc_status);
|
||||||
|
|
||||||
if (pub_id == 0) {
|
if (pub_id == nullptr) {
|
||||||
PX4_ERR("error publishing esc_status");
|
PX4_ERR("error publishing esc_status");
|
||||||
return -1;
|
return -1;
|
||||||
}
|
}
|
||||||
|
|
||||||
orb_advert_t pub_id_vc = orb_advertise(ORB_ID(vehicle_command), & m_vc);
|
orb_advert_t pub_id_vc = orb_advertise(ORB_ID(vehicle_command), & m_vc);
|
||||||
|
|
||||||
if (pub_id_vc == 0) {
|
if (pub_id_vc == nullptr) {
|
||||||
PX4_ERR("error publishing vehicle_command");
|
PX4_ERR("error publishing vehicle_command");
|
||||||
return -1;
|
return -1;
|
||||||
}
|
}
|
||||||
|
@ -129,7 +129,7 @@ int MuorbTestExample::PingPongTest()
|
||||||
int i = 0;
|
int i = 0;
|
||||||
orb_advert_t pub_id_vc = orb_advertise(ORB_ID(vehicle_command), & m_vc);
|
orb_advert_t pub_id_vc = orb_advertise(ORB_ID(vehicle_command), & m_vc);
|
||||||
|
|
||||||
if (pub_id_vc == 0) {
|
if (pub_id_vc == nullptr) {
|
||||||
PX4_ERR("error publishing vehicle_command");
|
PX4_ERR("error publishing vehicle_command");
|
||||||
return -1;
|
return -1;
|
||||||
}
|
}
|
||||||
|
|
|
@ -32,7 +32,7 @@
|
||||||
############################################################################
|
############################################################################
|
||||||
px4_add_module(
|
px4_add_module(
|
||||||
MODULE platforms__posix__tests__vcdev_test
|
MODULE platforms__posix__tests__vcdev_test
|
||||||
MAIN vcdevtest
|
MAIN vcdev_test
|
||||||
SRCS
|
SRCS
|
||||||
vcdevtest_main.cpp
|
vcdevtest_main.cpp
|
||||||
vcdevtest_start_posix.cpp
|
vcdevtest_start_posix.cpp
|
||||||
|
|
|
@ -66,7 +66,7 @@ static int writer_main(int argc, char *argv[])
|
||||||
return -px4_errno;
|
return -px4_errno;
|
||||||
}
|
}
|
||||||
|
|
||||||
int ret;
|
int ret = 0;
|
||||||
int i = 0;
|
int i = 0;
|
||||||
|
|
||||||
while (!g_exit) {
|
while (!g_exit) {
|
||||||
|
@ -188,7 +188,7 @@ VCDevExample::~VCDevExample()
|
||||||
{
|
{
|
||||||
if (_node) {
|
if (_node) {
|
||||||
delete _node;
|
delete _node;
|
||||||
_node = 0;
|
_node = nullptr;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -272,7 +272,7 @@ int VCDevExample::main()
|
||||||
|
|
||||||
_node = new VCDevNode();
|
_node = new VCDevNode();
|
||||||
|
|
||||||
if (_node == 0) {
|
if (_node == nullptr) {
|
||||||
PX4_INFO("Failed to allocate VCDevNode");
|
PX4_INFO("Failed to allocate VCDevNode");
|
||||||
return -ENOMEM;
|
return -ENOMEM;
|
||||||
}
|
}
|
||||||
|
@ -289,7 +289,7 @@ int VCDevExample::main()
|
||||||
return -px4_errno;
|
return -px4_errno;
|
||||||
}
|
}
|
||||||
|
|
||||||
void *p = 0;
|
void *p = nullptr;
|
||||||
int ret = px4_ioctl(fd, DIOC_GETPRIV, (unsigned long)&p);
|
int ret = px4_ioctl(fd, DIOC_GETPRIV, (unsigned long)&p);
|
||||||
|
|
||||||
if (ret < 0) {
|
if (ret < 0) {
|
||||||
|
@ -318,7 +318,7 @@ int VCDevExample::main()
|
||||||
SCHED_PRIORITY_MAX - 6,
|
SCHED_PRIORITY_MAX - 6,
|
||||||
2000,
|
2000,
|
||||||
writer_main,
|
writer_main,
|
||||||
(char *const *)NULL);
|
(char *const *)nullptr);
|
||||||
|
|
||||||
ret = 0;
|
ret = 0;
|
||||||
|
|
||||||
|
|
|
@ -47,8 +47,8 @@ static int daemon_task; /* Handle of deamon task / thread */
|
||||||
|
|
||||||
//using namespace px4;
|
//using namespace px4;
|
||||||
|
|
||||||
extern "C" __EXPORT int vcdevtest_main(int argc, char *argv[]);
|
extern "C" __EXPORT int vcdev_test_main(int argc, char *argv[]);
|
||||||
int vcdevtest_main(int argc, char *argv[])
|
int vcdev_test_main(int argc, char *argv[])
|
||||||
{
|
{
|
||||||
|
|
||||||
if (argc < 2) {
|
if (argc < 2) {
|
||||||
|
@ -69,7 +69,7 @@ int vcdevtest_main(int argc, char *argv[])
|
||||||
SCHED_PRIORITY_MAX - 5,
|
SCHED_PRIORITY_MAX - 5,
|
||||||
2000,
|
2000,
|
||||||
PX4_MAIN,
|
PX4_MAIN,
|
||||||
(argv) ? (char *const *)&argv[2] : (char *const *)NULL);
|
(argv) ? (char *const *)&argv[2] : (char *const *)nullptr);
|
||||||
|
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
|
@ -71,7 +71,7 @@ int wqueue_test_main(int argc, char *argv[])
|
||||||
SCHED_PRIORITY_MAX - 5,
|
SCHED_PRIORITY_MAX - 5,
|
||||||
2000,
|
2000,
|
||||||
PX4_MAIN,
|
PX4_MAIN,
|
||||||
(argv) ? (char *const *)&argv[2] : (char *const *)NULL);
|
(argv) ? (char *const *)&argv[2] : (char *const *)nullptr);
|
||||||
|
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
|
@ -96,10 +96,9 @@ const struct {
|
||||||
{"mavlink", mavlink_tests_main, 0},
|
{"mavlink", mavlink_tests_main, 0},
|
||||||
{"mc_pos_control", mc_pos_control_tests_main, 0},
|
{"mc_pos_control", mc_pos_control_tests_main, 0},
|
||||||
{"sf0x", sf0x_tests_main, 0},
|
{"sf0x", sf0x_tests_main, 0},
|
||||||
#ifndef __PX4_DARWIN
|
|
||||||
{"uorb", uorb_tests_main, 0},
|
{"uorb", uorb_tests_main, 0},
|
||||||
{"hysteresis", test_hysteresis, 0},
|
{"hysteresis", test_hysteresis, 0},
|
||||||
#endif /* __PX4_DARWIN */
|
|
||||||
{"mixer", test_mixer, OPT_NOJIGTEST},
|
{"mixer", test_mixer, OPT_NOJIGTEST},
|
||||||
{"autodeclination", test_autodeclination, 0},
|
{"autodeclination", test_autodeclination, 0},
|
||||||
{"bson", test_bson, 0},
|
{"bson", test_bson, 0},
|
||||||
|
|
Loading…
Reference in New Issue