mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 04:03:59 -04:00
AP_Common: example fix travis warning
missing function declaration implicit cast some style fix
This commit is contained in:
parent
3f4a3e535b
commit
2200302081
@ -5,25 +5,27 @@
|
|||||||
#include <AP_Common/AP_Common.h>
|
#include <AP_Common/AP_Common.h>
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
|
void setup();
|
||||||
|
void loop();
|
||||||
|
void test_high_low_byte(void);
|
||||||
|
|
||||||
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||||
|
|
||||||
void test_high_low_byte(void)
|
void test_high_low_byte(void)
|
||||||
{
|
{
|
||||||
uint16_t i;
|
|
||||||
uint8_t high, low;
|
|
||||||
|
|
||||||
// test each value from 0 to 300
|
// test each value from 0 to 300
|
||||||
for (i=0; i<=300; i++) {
|
for (uint16_t i = 0; i <= 300; i++) {
|
||||||
high = HIGHBYTE(i);
|
uint8_t high = HIGHBYTE(i);
|
||||||
low = LOWBYTE(i);
|
uint8_t low = LOWBYTE(i);
|
||||||
hal.console->printf("\ni:%u high:%u low:%u",(unsigned int)i, (unsigned int)high, (unsigned int)low);
|
hal.console->printf("\ni:%u high:%u low:%u", (unsigned int)i, (unsigned int)high, (unsigned int)low);
|
||||||
}
|
}
|
||||||
|
|
||||||
// test values from 300 to 65400 at increments of 200
|
// test values from 300 to 65400 at increments of 200
|
||||||
for (i=301; i<=65400; i+=200) {
|
for (uint16_t i = 301; i <= 65400; i += 200) {
|
||||||
high = HIGHBYTE(i);
|
uint8_t high = HIGHBYTE(i);
|
||||||
low = LOWBYTE(i);
|
uint8_t low = LOWBYTE(i);
|
||||||
hal.console->printf("\ni:%u high:%u low:%u",(unsigned int)i, (unsigned int)high, (unsigned int)low);
|
hal.console->printf("\ni:%u high:%u low:%u", (unsigned int)i, (unsigned int)high, (unsigned int)low);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user