diff options
author | Mark Charlebois <charlebm@gmail.com> | 2015-03-19 09:07:37 -0700 |
---|---|---|
committer | Mark Charlebois <charlebm@gmail.com> | 2015-04-20 11:15:12 -0700 |
commit | 62eb403e4d5e4f893a6584bcf926915804e853d3 (patch) | |
tree | a29e5bc07a81acd470e16875698e3d3d314dc41d | |
parent | 5f3496353ccf19e2e6f2253ada546b35f6fc51fc (diff) | |
download | px4-firmware-62eb403e4d5e4f893a6584bcf926915804e853d3.tar.gz px4-firmware-62eb403e4d5e4f893a6584bcf926915804e853d3.tar.bz2 px4-firmware-62eb403e4d5e4f893a6584bcf926915804e853d3.zip |
Linus: print format fixes to build with clang on IFC6410
Signed-off-by: Mark Charlebois <charlebm@gmail.com>
-rw-r--r-- | src/drivers/device/ringbuffer.h | 2 | ||||
-rw-r--r-- | src/drivers/ms5611/ms5611_linux.cpp | 4 | ||||
-rw-r--r-- | src/modules/mavlink/mavlink_main_linux.cpp | 2 | ||||
-rw-r--r-- | src/platforms/linux/tests/hrt_test/hrt_test.cpp | 8 |
4 files changed, 8 insertions, 8 deletions
diff --git a/src/drivers/device/ringbuffer.h b/src/drivers/device/ringbuffer.h index 35b38efd7..f03171722 100644 --- a/src/drivers/device/ringbuffer.h +++ b/src/drivers/device/ringbuffer.h @@ -506,7 +506,7 @@ RingBuffer::print_info(const char *name) printf("%s %u/%lu (%u/%u @ %p)\n", name, _num_items, - _num_items * _item_size, + (unsigned long)_num_items * _item_size, _head, _tail, _buf); diff --git a/src/drivers/ms5611/ms5611_linux.cpp b/src/drivers/ms5611/ms5611_linux.cpp index e914dfaec..913c1ebcd 100644 --- a/src/drivers/ms5611/ms5611_linux.cpp +++ b/src/drivers/ms5611/ms5611_linux.cpp @@ -445,7 +445,7 @@ MS5611::ioctl(device::px4_dev_handle_t *handlep, int cmd, unsigned long arg) unsigned ticks = USEC2TICK(1000000 / arg); /* check against maximum rate */ - if (ticks < USEC2TICK(MS5611_CONVERSION_INTERVAL)) + if ((long)ticks < USEC2TICK(MS5611_CONVERSION_INTERVAL)) return -EINVAL; /* update interval for next measurement */ @@ -572,7 +572,7 @@ MS5611::cycle() * doing pressure measurements at something close to the desired rate. */ if ((_measure_phase != 0) && - (_measure_ticks > USEC2TICK(MS5611_CONVERSION_INTERVAL))) { + ((long)_measure_ticks > USEC2TICK(MS5611_CONVERSION_INTERVAL))) { /* schedule a fresh cycle call when we are ready to measure again */ work_queue(HPWORK, diff --git a/src/modules/mavlink/mavlink_main_linux.cpp b/src/modules/mavlink/mavlink_main_linux.cpp index a6b49ee25..e251ceaf5 100644 --- a/src/modules/mavlink/mavlink_main_linux.cpp +++ b/src/modules/mavlink/mavlink_main_linux.cpp @@ -1657,7 +1657,7 @@ Mavlink::display_status() { if (_rstatus.heartbeat_time > 0) { - printf("\tGCS heartbeat:\t%lu us ago\n", hrt_elapsed_time(&_rstatus.heartbeat_time)); + printf("\tGCS heartbeat:\t%llu us ago\n", hrt_elapsed_time(&_rstatus.heartbeat_time)); } printf("\tmavlink chan: #%u\n", _channel); diff --git a/src/platforms/linux/tests/hrt_test/hrt_test.cpp b/src/platforms/linux/tests/hrt_test/hrt_test.cpp index 5677f4e1b..d5e446bcc 100644 --- a/src/platforms/linux/tests/hrt_test/hrt_test.cpp +++ b/src/platforms/linux/tests/hrt_test/hrt_test.cpp @@ -53,14 +53,14 @@ int HRTTest::main() hrt_abstime t = hrt_absolute_time(); usleep(1000000); hrt_abstime elt = hrt_elapsed_time(&t); - printf("Elapsed time %lu in 1 sec (usleep)\n", elt); - printf("Start time %lu\n", t); + printf("Elapsed time %llu in 1 sec (usleep)\n", elt); + printf("Start time %llu\n", t); t = hrt_absolute_time(); sleep(1); elt = hrt_elapsed_time(&t); - printf("Elapsed time %lu in 1 sec (sleep)\n", elt); - printf("Start time %lu\n", t); + printf("Elapsed time %llu in 1 sec (sleep)\n", elt); + printf("Start time %llu\n", t); return 0; } |