mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-28 02:33:58 -04:00
AP_HAL: example fix travis warning
missing function declaration implicit cast some style fix
This commit is contained in:
parent
292fa5f413
commit
34199b4af0
@ -1,24 +1,27 @@
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
void setup();
|
||||
void loop();
|
||||
|
||||
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||
|
||||
AP_HAL::AnalogSource* ch;
|
||||
|
||||
void setup (void) {
|
||||
void setup(void) {
|
||||
hal.console->printf("Starting AP_HAL::AnalogIn test\r\n");
|
||||
ch = hal.analogin->channel(0);
|
||||
}
|
||||
|
||||
static int8_t pin;
|
||||
|
||||
void loop (void)
|
||||
void loop(void)
|
||||
{
|
||||
float v = ch->voltage_average();
|
||||
if (pin == 0) {
|
||||
hal.console->printf("\n");
|
||||
}
|
||||
hal.console->printf("[%u %.3f] ",
|
||||
(unsigned)pin, v);
|
||||
(unsigned)pin, (double)v);
|
||||
pin = (pin+1) % 16;
|
||||
ch->set_pin(pin);
|
||||
hal.scheduler->delay(100);
|
||||
|
@ -1,6 +1,9 @@
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
void setup();
|
||||
void loop();
|
||||
|
||||
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||
|
||||
void setup(void) {
|
||||
@ -51,7 +54,7 @@ static void test_printf(void)
|
||||
uint8_t failures = 0;
|
||||
hal.console->printf("Running printf tests\n");
|
||||
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) {
|
||||
hal.console->printf("Failed float_tests[%u] '%s' -> '%s' should be '%s'\n",
|
||||
(unsigned)i,
|
||||
|
@ -4,11 +4,14 @@
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
void setup();
|
||||
void loop();
|
||||
|
||||
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||
|
||||
#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];
|
||||
|
||||
void setup(void)
|
||||
@ -19,11 +22,11 @@ void setup(void)
|
||||
void loop(void)
|
||||
{
|
||||
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) {
|
||||
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++) {
|
||||
uint16_t v = hal.rcin->read(i);
|
||||
if (last_value[i] != v) {
|
||||
|
@ -6,6 +6,9 @@
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
void setup();
|
||||
void loop();
|
||||
|
||||
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||
|
||||
#define MAX_CHANNELS 14
|
||||
@ -17,7 +20,7 @@ void setup(void)
|
||||
{
|
||||
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);
|
||||
}
|
||||
}
|
||||
@ -27,24 +30,24 @@ void loop(void)
|
||||
bool changed = false;
|
||||
uint8_t nchannels = hal.rcin->num_channels();
|
||||
|
||||
if(nchannels > MAX_CHANNELS) {
|
||||
if (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);
|
||||
if(last_value[i] != v) {
|
||||
if (last_value[i] != v) {
|
||||
hal.rcout->write(i, v);
|
||||
changed = true;
|
||||
last_value[i] = v;
|
||||
}
|
||||
if(i > max_channels) {
|
||||
if (i > max_channels) {
|
||||
max_channels = i;
|
||||
}
|
||||
}
|
||||
if(changed) {
|
||||
for(uint8_t i = 0; i < max_channels; i++) {
|
||||
hal.console->printf("%2u:%04u ", (unsigned)i + 1, (unsigned)last_value[i]);
|
||||
if (changed) {
|
||||
for (uint8_t i = 0; i < max_channels; i++) {
|
||||
hal.console->printf("%2u:%04u ", (unsigned)(i + 1), (unsigned)last_value[i]);
|
||||
}
|
||||
hal.console->printf("\n");
|
||||
}
|
||||
|
@ -4,12 +4,15 @@
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
void setup();
|
||||
void loop();
|
||||
|
||||
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||
|
||||
void setup (void)
|
||||
{
|
||||
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);
|
||||
}
|
||||
}
|
||||
@ -19,8 +22,7 @@ static int8_t delta = 1;
|
||||
|
||||
void loop (void)
|
||||
{
|
||||
uint8_t i;
|
||||
for (i=0; i<14; i++) {
|
||||
for (uint8_t i=0; i < 14; i++) {
|
||||
hal.rcout->write(i, pwm);
|
||||
pwm += delta;
|
||||
if (delta > 0 && pwm >= 2000) {
|
||||
|
@ -6,6 +6,10 @@
|
||||
#include <AP_HAL/AP_HAL.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 ESC_HZ 490
|
||||
|
@ -4,6 +4,9 @@
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
void setup();
|
||||
void loop();
|
||||
|
||||
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||
|
||||
AP_HAL::Storage *st;
|
||||
@ -20,15 +23,14 @@ void setup(void)
|
||||
Calculate XOR of the full conent of memory
|
||||
Do it by block of 8 bytes
|
||||
*/
|
||||
unsigned int i, j;
|
||||
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);
|
||||
for(j = 0; j < 8; j++)
|
||||
for(uint32_t j = 0; j < 8; j++) {
|
||||
XOR_res ^= buff[j];
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
print XORed result
|
||||
|
@ -8,6 +8,9 @@
|
||||
#include <stdio.h>
|
||||
#endif
|
||||
|
||||
void setup();
|
||||
void loop();
|
||||
|
||||
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||
|
||||
/*
|
||||
@ -42,7 +45,7 @@ static void test_uart(AP_HAL::UARTDriver *uart, const char *name)
|
||||
return;
|
||||
}
|
||||
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)
|
||||
@ -56,7 +59,7 @@ void loop(void)
|
||||
// also do a raw printf() on some platforms, which prints to the
|
||||
// debug console
|
||||
#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
|
||||
|
||||
hal.scheduler->delay(1000);
|
||||
|
Loading…
Reference in New Issue
Block a user