AP_HAL: example fix travis warning

missing function declaration
implicit cast
some style fix
This commit is contained in:
Pierre Kancir 2017-04-13 13:31:16 +02:00 committed by Francisco Ferreira
parent 292fa5f413
commit 34199b4af0
8 changed files with 62 additions and 39 deletions

View File

@ -1,24 +1,27 @@
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
void setup();
void loop();
const AP_HAL::HAL& hal = AP_HAL::get_HAL(); const AP_HAL::HAL& hal = AP_HAL::get_HAL();
AP_HAL::AnalogSource* ch; AP_HAL::AnalogSource* ch;
void setup (void) { void setup(void) {
hal.console->printf("Starting AP_HAL::AnalogIn test\r\n"); hal.console->printf("Starting AP_HAL::AnalogIn test\r\n");
ch = hal.analogin->channel(0); ch = hal.analogin->channel(0);
} }
static int8_t pin; static int8_t pin;
void loop (void) void loop(void)
{ {
float v = ch->voltage_average(); float v = ch->voltage_average();
if (pin == 0) { if (pin == 0) {
hal.console->printf("\n"); hal.console->printf("\n");
} }
hal.console->printf("[%u %.3f] ", hal.console->printf("[%u %.3f] ",
(unsigned)pin, v); (unsigned)pin, (double)v);
pin = (pin+1) % 16; pin = (pin+1) % 16;
ch->set_pin(pin); ch->set_pin(pin);
hal.scheduler->delay(100); hal.scheduler->delay(100);

View File

@ -1,6 +1,9 @@
#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();
const AP_HAL::HAL& hal = AP_HAL::get_HAL(); const AP_HAL::HAL& hal = AP_HAL::get_HAL();
void setup(void) { void setup(void) {
@ -51,7 +54,7 @@ static void test_printf(void)
uint8_t failures = 0; uint8_t failures = 0;
hal.console->printf("Running printf tests\n"); hal.console->printf("Running printf tests\n");
for (i=0; i < ARRAY_SIZE(float_tests); i++) { for (i=0; i < ARRAY_SIZE(float_tests); i++) {
int ret = hal.util->snprintf(buf, sizeof(buf), float_tests[i].fmt, float_tests[i].v); int ret = hal.util->snprintf(buf, sizeof(buf), float_tests[i].fmt, (double)float_tests[i].v);
if (strcmp(buf, float_tests[i].result) != 0) { if (strcmp(buf, float_tests[i].result) != 0) {
hal.console->printf("Failed float_tests[%u] '%s' -> '%s' should be '%s'\n", hal.console->printf("Failed float_tests[%u] '%s' -> '%s' should be '%s'\n",
(unsigned)i, (unsigned)i,

View File

@ -4,14 +4,17 @@
#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();
const AP_HAL::HAL& hal = AP_HAL::get_HAL(); const AP_HAL::HAL& hal = AP_HAL::get_HAL();
#define MAX_CHANNELS 16 #define MAX_CHANNELS 16
static uint8_t max_channels_display = 8; //Set to 0 for display numbers of channels detected. static uint8_t max_channels_display = 8; // Set to 0 for display numbers of channels detected.
static uint16_t last_value[MAX_CHANNELS]; static uint16_t last_value[MAX_CHANNELS];
void setup(void) void setup(void)
{ {
hal.console->printf("Starting RCInput test\n"); hal.console->printf("Starting RCInput test\n");
} }
@ -19,11 +22,11 @@ void setup(void)
void loop(void) void loop(void)
{ {
bool changed = false; bool changed = false;
uint8_t nchannels = hal.rcin->num_channels(); //Get the numbers channels detected by RC_INPUT. uint8_t nchannels = hal.rcin->num_channels(); // Get the numbers channels detected by RC_INPUT.
if (nchannels > MAX_CHANNELS) { if (nchannels > MAX_CHANNELS) {
nchannels = MAX_CHANNELS; nchannels = MAX_CHANNELS;
} }
if (nchannels != 0) { //If channels detected, process. if (nchannels != 0) { // If channels detected, process.
for (uint8_t i = 0; i < nchannels; i++) { for (uint8_t i = 0; i < nchannels; i++) {
uint16_t v = hal.rcin->read(i); uint16_t v = hal.rcin->read(i);
if (last_value[i] != v) { if (last_value[i] != v) {

View File

@ -6,6 +6,9 @@
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
void setup();
void loop();
const AP_HAL::HAL& hal = AP_HAL::get_HAL(); const AP_HAL::HAL& hal = AP_HAL::get_HAL();
#define MAX_CHANNELS 14 #define MAX_CHANNELS 14
@ -13,38 +16,38 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();
static uint8_t max_channels = 0; static uint8_t max_channels = 0;
static uint16_t last_value[MAX_CHANNELS]; static uint16_t last_value[MAX_CHANNELS];
void setup(void) void setup(void)
{ {
hal.console->printf("Starting RCInputToRCOutput test\n"); hal.console->printf("Starting RCInputToRCOutput test\n");
for(uint8_t i = 0; i < MAX_CHANNELS; i++) { for (uint8_t i = 0; i < MAX_CHANNELS; i++) {
hal.rcout->enable_ch(i); hal.rcout->enable_ch(i);
} }
} }
void loop(void) void loop(void)
{ {
bool changed = false; bool changed = false;
uint8_t nchannels = hal.rcin->num_channels(); uint8_t nchannels = hal.rcin->num_channels();
if(nchannels > MAX_CHANNELS) { if (nchannels > MAX_CHANNELS) {
nchannels = MAX_CHANNELS; nchannels = MAX_CHANNELS;
} }
for(uint8_t i = 0; i < nchannels; i++) { for (uint8_t i = 0; i < nchannels; i++) {
uint16_t v = hal.rcin->read(i); uint16_t v = hal.rcin->read(i);
if(last_value[i] != v) { if (last_value[i] != v) {
hal.rcout->write(i, v); hal.rcout->write(i, v);
changed = true; changed = true;
last_value[i] = v; last_value[i] = v;
} }
if(i > max_channels) { if (i > max_channels) {
max_channels = i; max_channels = i;
} }
} }
if(changed) { if (changed) {
for(uint8_t i = 0; i < max_channels; i++) { for (uint8_t i = 0; i < max_channels; i++) {
hal.console->printf("%2u:%04u ", (unsigned)i + 1, (unsigned)last_value[i]); hal.console->printf("%2u:%04u ", (unsigned)(i + 1), (unsigned)last_value[i]);
} }
hal.console->printf("\n"); hal.console->printf("\n");
} }

View File

@ -4,12 +4,15 @@
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
void setup();
void loop();
const AP_HAL::HAL& hal = AP_HAL::get_HAL(); const AP_HAL::HAL& hal = AP_HAL::get_HAL();
void setup (void) void setup (void)
{ {
hal.console->printf("Starting AP_HAL::RCOutput test\n"); hal.console->printf("Starting AP_HAL::RCOutput test\n");
for (uint8_t i=0; i<14; i++) { for (uint8_t i = 0; i< 14; i++) {
hal.rcout->enable_ch(i); hal.rcout->enable_ch(i);
} }
} }
@ -17,10 +20,9 @@ void setup (void)
static uint16_t pwm = 1500; static uint16_t pwm = 1500;
static int8_t delta = 1; static int8_t delta = 1;
void loop (void) void loop (void)
{ {
uint8_t i; for (uint8_t i=0; i < 14; i++) {
for (i=0; i<14; i++) {
hal.rcout->write(i, pwm); hal.rcout->write(i, pwm);
pwm += delta; pwm += delta;
if (delta > 0 && pwm >= 2000) { if (delta > 0 && pwm >= 2000) {

View File

@ -6,6 +6,10 @@
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
#include <AP_Menu/AP_Menu.h> #include <AP_Menu/AP_Menu.h>
void setup();
void loop();
void drive(uint16_t hz_speed);
#define MENU_FUNC(func) FUNCTOR_BIND(&commands, &Menu_Commands::func, int8_t, uint8_t, const Menu::arg *) #define MENU_FUNC(func) FUNCTOR_BIND(&commands, &Menu_Commands::func, int8_t, uint8_t, const Menu::arg *)
#define ESC_HZ 490 #define ESC_HZ 490

View File

@ -4,6 +4,9 @@
#include <AP_HAL/AP_HAL.h> #include <AP_HAL/AP_HAL.h>
void setup();
void loop();
const AP_HAL::HAL& hal = AP_HAL::get_HAL(); const AP_HAL::HAL& hal = AP_HAL::get_HAL();
AP_HAL::Storage *st; AP_HAL::Storage *st;
@ -20,14 +23,13 @@ void setup(void)
Calculate XOR of the full conent of memory Calculate XOR of the full conent of memory
Do it by block of 8 bytes Do it by block of 8 bytes
*/ */
unsigned int i, j;
unsigned char buff[8], XOR_res = 0; unsigned char buff[8], XOR_res = 0;
for(i = 0; i < HAL_STORAGE_SIZE; i += 8) for (uint32_t i = 0; i < HAL_STORAGE_SIZE; i += 8) {
{
st->read_block((void *) buff, i, 8); st->read_block((void *) buff, i, 8);
for(j = 0; j < 8; j++) for(uint32_t j = 0; j < 8; j++) {
XOR_res ^= buff[j]; XOR_res ^= buff[j];
}
} }
/* /*

View File

@ -8,6 +8,9 @@
#include <stdio.h> #include <stdio.h>
#endif #endif
void setup();
void loop();
const AP_HAL::HAL& hal = AP_HAL::get_HAL(); const AP_HAL::HAL& hal = AP_HAL::get_HAL();
/* /*
@ -23,16 +26,16 @@ static void setup_uart(AP_HAL::UARTDriver *uart, const char *name)
} }
void setup(void) void setup(void)
{ {
/* /*
start all UARTs at 57600 with default buffer sizes start all UARTs at 57600 with default buffer sizes
*/ */
setup_uart(hal.uartA, "uartA"); // console setup_uart(hal.uartA, "uartA"); // console
setup_uart(hal.uartB, "uartB"); // 1st GPS setup_uart(hal.uartB, "uartB"); // 1st GPS
setup_uart(hal.uartC, "uartC"); // telemetry 1 setup_uart(hal.uartC, "uartC"); // telemetry 1
setup_uart(hal.uartD, "uartD"); // telemetry 2 setup_uart(hal.uartD, "uartD"); // telemetry 2
setup_uart(hal.uartE, "uartE"); // 2nd GPS setup_uart(hal.uartE, "uartE"); // 2nd GPS
} }
static void test_uart(AP_HAL::UARTDriver *uart, const char *name) static void test_uart(AP_HAL::UARTDriver *uart, const char *name)
@ -42,11 +45,11 @@ static void test_uart(AP_HAL::UARTDriver *uart, const char *name)
return; return;
} }
uart->printf("Hello on UART %s at %.3f seconds\n", uart->printf("Hello on UART %s at %.3f seconds\n",
name, AP_HAL::millis()*0.001f); name, (double)(AP_HAL::millis() * 0.001f));
} }
void loop(void) void loop(void)
{ {
test_uart(hal.uartA, "uartA"); test_uart(hal.uartA, "uartA");
test_uart(hal.uartB, "uartB"); test_uart(hal.uartB, "uartB");
test_uart(hal.uartC, "uartC"); test_uart(hal.uartC, "uartC");
@ -56,7 +59,7 @@ void loop(void)
// also do a raw printf() on some platforms, which prints to the // also do a raw printf() on some platforms, which prints to the
// debug console // debug console
#if HAL_OS_POSIX_IO #if HAL_OS_POSIX_IO
::printf("Hello on debug console at %.3f seconds\n", AP_HAL::millis()*0.001f); ::printf("Hello on debug console at %.3f seconds\n", (double)(AP_HAL::millis() * 0.001f));
#endif #endif
hal.scheduler->delay(1000); hal.scheduler->delay(1000);