mirror of
https://gitee.com/xiaohuolufeihua/bizhang_-obav.git
synced 2026-05-22 01:12:31 +00:00
Linus: print format fixes to build with clang on IFC6410
Signed-off-by: Mark Charlebois <charlebm@gmail.com>
This commit is contained in:
@@ -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);
|
||||
|
||||
@@ -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,
|
||||
|
||||
@@ -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);
|
||||
|
||||
@@ -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;
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user