From 8b76d5e941796860ce3777263c1244008f8e9ee5 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 23 Dec 2015 09:12:29 +0100 Subject: [PATCH] Update simple app example to use multiplatform API --- src/examples/px4_simple_app/px4_simple_app.c | 15 +++++++++------ 1 file changed, 9 insertions(+), 6 deletions(-) diff --git a/src/examples/px4_simple_app/px4_simple_app.c b/src/examples/px4_simple_app/px4_simple_app.c index ea54574bb9..6007d1fa44 100644 --- a/src/examples/px4_simple_app/px4_simple_app.c +++ b/src/examples/px4_simple_app/px4_simple_app.c @@ -39,6 +39,8 @@ */ #include +#include +#include #include #include #include @@ -52,7 +54,7 @@ __EXPORT int px4_simple_app_main(int argc, char *argv[]); int px4_simple_app_main(int argc, char *argv[]) { - printf("Hello Sky!\n"); + PX4_INFO("Hello Sky!"); /* subscribe to sensor_combined topic */ int sensor_sub_fd = orb_subscribe(ORB_ID(sensor_combined)); @@ -64,7 +66,7 @@ int px4_simple_app_main(int argc, char *argv[]) orb_advert_t att_pub = orb_advertise(ORB_ID(vehicle_attitude), &att); /* one could wait for multiple topics with this technique, just using one here */ - struct pollfd fds[] = { + px4_pollfd_struct_t fds[] = { { .fd = sensor_sub_fd, .events = POLLIN }, /* there could be more file descriptors here, in the form like: * { .fd = other_sub_fd, .events = POLLIN }, @@ -75,18 +77,18 @@ int px4_simple_app_main(int argc, char *argv[]) for (int i = 0; i < 5; i++) { /* wait for sensor update of 1 file descriptor for 1000 ms (1 second) */ - int poll_ret = poll(fds, 1, 1000); + int poll_ret = px4_poll(fds, 1, 1000); /* handle the poll result */ if (poll_ret == 0) { /* this means none of our providers is giving us data */ - printf("[px4_simple_app] Got no data within a second\n"); + PX4_ERR("[px4_simple_app] Got no data within a second"); } else if (poll_ret < 0) { /* this is seriously bad - should be an emergency */ if (error_counter < 10 || error_counter % 50 == 0) { /* use a counter to prevent flooding (and slowing us down) */ - printf("[px4_simple_app] ERROR return value from poll(): %d\n" + PX4_ERR("[px4_simple_app] ERROR return value from poll(): %d" , poll_ret); } @@ -99,7 +101,7 @@ int px4_simple_app_main(int argc, char *argv[]) struct sensor_combined_s raw; /* copy sensors raw data into local buffer */ orb_copy(ORB_ID(sensor_combined), sensor_sub_fd, &raw); - printf("[px4_simple_app] Accelerometer:\t%8.4f\t%8.4f\t%8.4f\n", + PX4_WARN("[px4_simple_app] Accelerometer:\t%8.4f\t%8.4f\t%8.4f", (double)raw.accelerometer_m_s2[0], (double)raw.accelerometer_m_s2[1], (double)raw.accelerometer_m_s2[2]); @@ -116,6 +118,7 @@ int px4_simple_app_main(int argc, char *argv[]) */ } } + PX4_INFO("exiting"); return 0; }