forked from Archive/PX4-Autopilot
QuRT: enable uORB, and simulator
uORB, the simulator and simulated devices now run Signed-off-by: Mark Charlebois <charlebm@gmail.com>
This commit is contained in:
parent
884f62878d
commit
8e346a06fb
|
@ -13,7 +13,7 @@
|
|||
MODULES += drivers/device
|
||||
#MODULES += drivers/blinkm
|
||||
#MODULES += drivers/hil
|
||||
#MODULES += drivers/led
|
||||
MODULES += drivers/led
|
||||
#MODULES += drivers/rgbled
|
||||
#MODULES += modules/sensors
|
||||
#MODULES += drivers/ms5611
|
||||
|
@ -47,32 +47,32 @@ MODULES += modules/systemlib
|
|||
MODULES += modules/uORB
|
||||
#MODULES += modules/dataman
|
||||
#MODULES += modules/sdlog2
|
||||
#MODULES += modules/simulator
|
||||
MODULES += modules/simulator
|
||||
#MODULES += modules/commander
|
||||
|
||||
#
|
||||
# Libraries
|
||||
#
|
||||
#MODULES += lib/mathlib
|
||||
#MODULES += lib/mathlib/math/filter
|
||||
MODULES += lib/mathlib
|
||||
MODULES += lib/mathlib/math/filter
|
||||
#MODULES += lib/geo
|
||||
#MODULES += lib/geo_lookup
|
||||
#MODULES += lib/conversion
|
||||
MODULES += lib/conversion
|
||||
|
||||
#
|
||||
# QuRT port
|
||||
#
|
||||
MODULES += platforms/qurt/px4_layer
|
||||
#MODULES += platforms/posix/drivers/accelsim
|
||||
#MODULES += platforms/posix/drivers/gyrosim
|
||||
#MODULES += platforms/posix/drivers/adcsim
|
||||
#MODULES += platforms/posix/drivers/barosim
|
||||
MODULES += platforms/posix/drivers/accelsim
|
||||
MODULES += platforms/posix/drivers/gyrosim
|
||||
MODULES += platforms/posix/drivers/adcsim
|
||||
MODULES += platforms/posix/drivers/barosim
|
||||
|
||||
#
|
||||
# Unit tests
|
||||
#
|
||||
MODULES += platforms/qurt/tests/hello
|
||||
#MODULES += platforms/posix/tests/vcdev_test
|
||||
#MODULES += platforms/posix/tests/hrt_test
|
||||
#MODULES += platforms/posix/tests/wqueue
|
||||
MODULES += platforms/posix/tests/vcdev_test
|
||||
MODULES += platforms/posix/tests/hrt_test
|
||||
MODULES += platforms/posix/tests/wqueue
|
||||
|
||||
|
|
|
@ -56,11 +56,12 @@ $(PRODUCT_SHARED_PRELINK): $(OBJS) $(MODULE_OBJS) $(LIBRARY_LIBS) $(GLOBAL_DEPS)
|
|||
$(PRODUCT_SHARED_LIB): $(PRODUCT_SHARED_PRELINK)
|
||||
$(call LINK_A,$@,$(PRODUCT_SHARED_PRELINK))
|
||||
|
||||
$(WORK_DIR)apps.cpp: $(PX4_BASE)/Tools/qurt_apps.py
|
||||
$(WORK_DIR)apps.cpp: $(PX4_BASE)/Tools/qurt_apps.py
|
||||
$(PX4_BASE)/Tools/qurt_apps.py > $@
|
||||
|
||||
$(WORK_DIR)apps.o: $(WORK_DIR)apps.cpp
|
||||
$(call COMPILEXX,$<, $@)
|
||||
mv $(WORK_DIR)apps.cpp $(WORK_DIR)apps.cpp_sav
|
||||
|
||||
$(WORK_DIR)mainapp: $(WORK_DIR)apps.o $(PRODUCT_SHARED_LIB)
|
||||
$(call LINK,$@, $^)
|
||||
|
|
|
@ -37,6 +37,7 @@
|
|||
* @author Mark Charlebois <mcharleb@gmail.com>
|
||||
*/
|
||||
#include "hrt_test.h"
|
||||
#include <px4_log.h>
|
||||
#include <px4_app.h>
|
||||
#include <px4_tasks.h>
|
||||
#include <stdio.h>
|
||||
|
|
|
@ -190,16 +190,20 @@ int VCDevExample::main()
|
|||
px4_close(fd);
|
||||
}
|
||||
else if (i > 0) {
|
||||
if (ret == 0)
|
||||
if (ret == 0) {
|
||||
PX4_INFO("==== Nothing to read - PASS\n");
|
||||
else
|
||||
}
|
||||
else {
|
||||
PX4_INFO("==== poll returned %d\n", ret);
|
||||
}
|
||||
}
|
||||
else if (i == 0) {
|
||||
if (ret == 1)
|
||||
if (ret == 1) {
|
||||
PX4_INFO("==== %d to read - %s\n", ret, fds[0].revents & POLLIN ? "PASS" : "FAIL");
|
||||
else
|
||||
}
|
||||
else {
|
||||
PX4_INFO("==== %d to read - FAIL\n", ret);
|
||||
}
|
||||
|
||||
}
|
||||
++i;
|
||||
|
|
|
@ -51,14 +51,17 @@ extern void init_app_map(map<string,px4_main_t> &apps);
|
|||
extern void list_builtins(map<string,px4_main_t> &apps);
|
||||
|
||||
static const char *commands =
|
||||
"hello start"
|
||||
#if 0
|
||||
"hello start\n"
|
||||
"uorb start\n"
|
||||
"simulator start -s\n"
|
||||
"barosim start\n"
|
||||
"adcsim start\n"
|
||||
"accelsim start\n"
|
||||
"gyrosim start\n"
|
||||
"list_devices\n"
|
||||
"list_topics\n"
|
||||
"list_tasks"
|
||||
#if 0
|
||||
"param set CAL_GYRO0_ID 2293760\n"
|
||||
"param set CAL_ACC0_ID 1310720\n"
|
||||
"param set CAL_ACC1_ID 1376256\n"
|
||||
|
@ -68,8 +71,6 @@ static const char *commands =
|
|||
"sensors start\n"
|
||||
"hil mode_pwm\n"
|
||||
"commander start\n"
|
||||
"list_devices\n"
|
||||
"list_topics\n"
|
||||
#endif
|
||||
;
|
||||
|
||||
|
@ -82,7 +83,7 @@ static void run_cmd(map<string,px4_main_t> &apps, const vector<string> &appargs)
|
|||
unsigned int i = 0;
|
||||
while (i < appargs.size() && appargs[i].c_str()[0] != '\0') {
|
||||
arg[i] = (char *)appargs[i].c_str();
|
||||
printf(" arg = '%s'\n", arg[i]);
|
||||
//printf(" arg = '%s'\n", arg[i]);
|
||||
++i;
|
||||
}
|
||||
arg[i] = (char *)0;
|
||||
|
@ -141,7 +142,6 @@ static void process_commands(map<string,px4_main_t> &apps, const char *cmds)
|
|||
eat_whitespace(b, ++i);
|
||||
continue;
|
||||
}
|
||||
printf("ch %c\n", b[i]);
|
||||
++i;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -81,12 +81,9 @@ static void *entry_adapter ( void *ptr )
|
|||
pthdata_t *data;
|
||||
data = (pthdata_t *) ptr;
|
||||
|
||||
PX4_DBG("entry_adapter");
|
||||
data->entry(data->argc, data->argv);
|
||||
free(ptr);
|
||||
PX4_DBG("Before px4_task_exit");
|
||||
px4_task_exit(0);
|
||||
PX4_DBG("After px4_task_exit");
|
||||
|
||||
return NULL;
|
||||
}
|
||||
|
|
|
@ -52,7 +52,7 @@ int HelloExample::main()
|
|||
int i=0;
|
||||
while (!appState.exitRequested() && i<5) {
|
||||
|
||||
PX4_DEBUG(" Doing work...\n");
|
||||
PX4_DEBUG(" Doing work...");
|
||||
++i;
|
||||
}
|
||||
|
||||
|
|
|
@ -47,10 +47,10 @@ int PX4_MAIN(int argc, char **argv)
|
|||
{
|
||||
px4::init(argc, argv, "hello");
|
||||
|
||||
PX4_DEBUG("hello\n");
|
||||
PX4_DEBUG("hello");
|
||||
HelloExample hello;
|
||||
hello.main();
|
||||
|
||||
PX4_DEBUG("goodbye\n");
|
||||
PX4_DEBUG("goodbye");
|
||||
return 0;
|
||||
}
|
||||
|
|
|
@ -53,11 +53,10 @@ extern "C" __EXPORT int hello_main(int argc, char *argv[]);
|
|||
|
||||
static void usage()
|
||||
{
|
||||
PX4_DEBUG("usage: hello {start|stop|status}\n");
|
||||
PX4_DEBUG("usage: hello {start|stop|status}");
|
||||
}
|
||||
int hello_main(int argc, char *argv[])
|
||||
{
|
||||
PX4_DEBUG("argc = %d %s %s %p\n", argc, argv[0], argv[1], argv[2]);
|
||||
if (argc < 2) {
|
||||
usage();
|
||||
return 1;
|
||||
|
@ -65,9 +64,8 @@ int hello_main(int argc, char *argv[])
|
|||
|
||||
if (!strcmp(argv[1], "start")) {
|
||||
|
||||
PX4_DEBUG("Starting\n");
|
||||
if (HelloExample::appState.isRunning()) {
|
||||
PX4_DEBUG("already running\n");
|
||||
PX4_DEBUG("already running");
|
||||
/* this is not an error */
|
||||
return 0;
|
||||
}
|
||||
|
@ -89,10 +87,10 @@ int hello_main(int argc, char *argv[])
|
|||
|
||||
if (!strcmp(argv[1], "status")) {
|
||||
if (HelloExample::appState.isRunning()) {
|
||||
PX4_DEBUG("is running\n");
|
||||
PX4_DEBUG("is running");
|
||||
|
||||
} else {
|
||||
PX4_DEBUG("not started\n");
|
||||
PX4_DEBUG("not started");
|
||||
}
|
||||
|
||||
return 0;
|
||||
|
|
Loading…
Reference in New Issue