diff --git a/src/platforms/qurt/main.cpp b/src/platforms/qurt/main.cpp index 55f9ad9a8d..217fa68d0c 100644 --- a/src/platforms/qurt/main.cpp +++ b/src/platforms/qurt/main.cpp @@ -51,8 +51,25 @@ #include "apps.h" #include "px4_middleware.h" -static const char *commands = "hello start\n" - "list_tasks"; +static const char *commands = +"uorb start\n" +"simulator start -s\n" +"barosim start\n" +"adcsim start\n" +"accelsim start\n" +"gyrosim start\n" +"param set CAL_GYRO0_ID 2293760\n" +"param set CAL_ACC0_ID 1310720\n" +"param set CAL_ACC1_ID 1376256\n" +"param set CAL_MAG0_ID 196608\n" +"rgbled start\n" +"mavlink start -d /tmp/ttyS0\n" +"sensors start\n" +"hil mode_pwm\n" +"commander start\n" +"list_devices\n" +"list_topics\n"; + static void run_cmd(const vector &appargs) { // command is appargs[0] diff --git a/src/platforms/qurt/px4_layer/px4_qurt_impl.cpp b/src/platforms/qurt/px4_layer/px4_qurt_impl.cpp index 36c795a213..5b7df7d6df 100644 --- a/src/platforms/qurt/px4_layer/px4_qurt_impl.cpp +++ b/src/platforms/qurt/px4_layer/px4_qurt_impl.cpp @@ -40,6 +40,7 @@ #include #include #include +#include #include #include #include @@ -52,6 +53,9 @@ __BEGIN_DECLS // FIXME - sysconf(_SC_CLK_TCK) not supported long PX4_TICKS_PER_SEC = 1000; +void usleep(useconds_t usec) {} +unsigned int sleep(unsigned int sec) { return 0; } + __END_DECLS extern struct wqueue_s gwork[NWORKERS]; @@ -83,3 +87,36 @@ void init(int argc, char *argv[], const char *app_name) } +/** Retrieve from the data manager store */ +ssize_t +dm_read( + dm_item_t item, /* The item type to retrieve */ + unsigned char index, /* The index of the item */ + void *buffer, /* Pointer to caller data buffer */ + size_t buflen /* Length in bytes of data to retrieve */ +) +{ + return 0; +} + +/** write to the data manager store */ +ssize_t +dm_write( + dm_item_t item, /* The item type to store */ + unsigned char index, /* The index of the item */ + dm_persitence_t persistence, /* The persistence level of this item */ + const void *buffer, /* Pointer to caller data buffer */ + size_t buflen /* Length in bytes of data to retrieve */ +) +{ + return 0; +} + +size_t strnlen(const char *s, size_t maxlen) +{ + size_t i=0; + while (s[i] != '\0' && i < maxlen) + ++i; + + return i; +}