mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
Various example sketches: hal.uart0->begin(115200) is redundant. use console.
just assume uart0 is initialized by the HAL, because it is. DRY. also, don't ever use uart0 explicitly in example sketches, use console and let the hal figure it out.
This commit is contained in:
parent
11cfde1e46
commit
c56c4ae240
@ -22,7 +22,6 @@ const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
||||
// setup function
|
||||
void setup()
|
||||
{
|
||||
hal.uart0->begin(115200);
|
||||
hal.console->println("ArduPilot Mega AC_PID library test");
|
||||
|
||||
hal.scheduler->delay(1000);
|
||||
|
@ -42,7 +42,6 @@ void print_latlon(AP_HAL::BetterStream *s, int32_t lat_or_lon)
|
||||
|
||||
void setup()
|
||||
{
|
||||
hal.uart0->begin(115200);
|
||||
hal.uart1->begin(38400);
|
||||
|
||||
hal.uart0->println("GPS AUTO library test");
|
||||
|
@ -6,7 +6,7 @@
|
||||
const AP_HAL::HAL& hal = AP_HAL_AVR_APM1;
|
||||
|
||||
void loop (void) {
|
||||
hal.uart0->println(".");
|
||||
hal.console->println(".");
|
||||
hal.gpio->write(3, 0);
|
||||
hal.scheduler->delay(1000);
|
||||
hal.gpio->write(3, 1);
|
||||
@ -33,9 +33,8 @@ void setup (void) {
|
||||
|
||||
hal.gpio->write(13, 1);
|
||||
|
||||
hal.uart0->begin(115200);
|
||||
hal.gpio->write(1, 0);
|
||||
hal.uart0->println("Hello World");
|
||||
hal.console->println("Hello World");
|
||||
hal.gpio->write(2, 0);
|
||||
}
|
||||
|
||||
|
@ -70,10 +70,6 @@ void stream_console_loopback(AP_HAL::Stream* s, AP_HAL::ConsoleDriver* c,
|
||||
}
|
||||
void setup(void)
|
||||
{
|
||||
//
|
||||
// Set the speed for our replacement serial port.
|
||||
//
|
||||
hal.uart0->begin(115200);
|
||||
//
|
||||
// Test printing things
|
||||
//
|
||||
|
@ -159,7 +159,6 @@ void longtest_readback()
|
||||
|
||||
void setup()
|
||||
{
|
||||
hal.uart0->begin(115200);
|
||||
hal.dataflash->init(NULL);
|
||||
|
||||
hal.uart0->println("Dataflash Log Test 1.0");
|
||||
|
@ -15,9 +15,9 @@ const AP_HAL::HAL& hal = AP_HAL_AVR_APM1;
|
||||
void setup(void)
|
||||
{
|
||||
//
|
||||
// Set the speed for our replacement serial port.
|
||||
// HAL will start serial port at 115200.
|
||||
//
|
||||
hal.uart0->begin(115200);
|
||||
|
||||
//
|
||||
// Test printing things
|
||||
//
|
||||
|
@ -13,16 +13,14 @@ const AP_HAL_AVR::HAL_AVR& hal = AP_HAL_AVR_APM2;
|
||||
#define HMC5883L 0x1E
|
||||
|
||||
void setup() {
|
||||
hal.uart0->begin(115200);
|
||||
hal.uart0->printf_P(PSTR("Initializing HMC5883L at address %x\r\n"),
|
||||
hal.console->printf_P(PSTR("Initializing HMC5883L at address %x\r\n"),
|
||||
HMC5883L);
|
||||
|
||||
|
||||
uint8_t stat = hal.i2c->writeRegister(HMC5883L,0x02,0x00);
|
||||
if (stat == 0) {
|
||||
hal.uart0->printf_P(PSTR("successful init\r\n"));
|
||||
hal.console->printf_P(PSTR("successful init\r\n"));
|
||||
} else {
|
||||
hal.uart0->printf_P(PSTR("failed init: return status %d\r\n"),
|
||||
hal.console->printf_P(PSTR("failed init: return status %d\r\n"),
|
||||
(int)stat);
|
||||
for(;;);
|
||||
}
|
||||
@ -41,9 +39,9 @@ void loop() {
|
||||
y |= data[3];
|
||||
z = data[4] << 8;
|
||||
z |= data[5];
|
||||
hal.uart0->printf_P(PSTR("x: %d y: %d z: %d \r\n"), x, y, z);
|
||||
hal.console->printf_P(PSTR("x: %d y: %d z: %d \r\n"), x, y, z);
|
||||
} else {
|
||||
hal.uart0->printf_P(PSTR("i2c error: status %d\r\n"), (int)stat);
|
||||
hal.console->printf_P(PSTR("i2c error: status %d\r\n"), (int)stat);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -10,7 +10,8 @@ void multiread(AP_HAL::RCInput* in) {
|
||||
uint16_t channels[8];
|
||||
uint8_t valid;
|
||||
valid = in->read(channels, 8);
|
||||
hal.uart0->printf_P(PSTR("multi read %d: %d %d %d %d %d %d %d %d\r\n"),
|
||||
hal.console->printf_P(
|
||||
PSTR("multi read %d: %d %d %d %d %d %d %d %d\r\n"),
|
||||
(int) valid,
|
||||
channels[0], channels[1], channels[2], channels[3],
|
||||
channels[4], channels[5], channels[6], channels[7]);
|
||||
@ -24,7 +25,8 @@ void individualread(AP_HAL::RCInput* in) {
|
||||
for (int i = 0; i < 8; i++) {
|
||||
channels[i] = in->read(i);
|
||||
}
|
||||
hal.uart0->printf_P(PSTR("individual read %d: %d %d %d %d %d %d %d %d\r\n"),
|
||||
hal.console->printf_P(
|
||||
PSTR("individual read %d: %d %d %d %d %d %d %d %d\r\n"),
|
||||
(int) valid,
|
||||
channels[0], channels[1], channels[2], channels[3],
|
||||
channels[4], channels[5], channels[6], channels[7]);
|
||||
@ -50,8 +52,7 @@ void loop (void) {
|
||||
}
|
||||
|
||||
void setup (void) {
|
||||
hal.uart0->begin(115200);
|
||||
hal.uart0->printf_P(PSTR("reading rc in:"));
|
||||
hal.console->printf_P(PSTR("reading rc in:"));
|
||||
hal.gpio->pinMode(27, GPIO_OUTPUT);
|
||||
hal.gpio->write(27, 0);
|
||||
}
|
||||
|
@ -9,7 +9,8 @@ void multiread(AP_HAL::RCInput* in, uint16_t* channels) {
|
||||
/* Multi-channel read method: */
|
||||
uint8_t valid;
|
||||
valid = in->read(channels, 8);
|
||||
hal.uart0->printf_P(PSTR("multi read %d: %d %d %d %d %d %d %d %d\r\n"),
|
||||
hal.console->printf_P(
|
||||
PSTR("multi read %d: %d %d %d %d %d %d %d %d\r\n"),
|
||||
(int) valid,
|
||||
channels[0], channels[1], channels[2], channels[3],
|
||||
channels[4], channels[5], channels[6], channels[7]);
|
||||
@ -22,7 +23,8 @@ void individualread(AP_HAL::RCInput* in, uint16_t* channels) {
|
||||
for (int i = 0; i < 8; i++) {
|
||||
channels[i] = in->read(i);
|
||||
}
|
||||
hal.uart0->printf_P(PSTR("individual read %d: %d %d %d %d %d %d %d %d\r\n"),
|
||||
hal.console->printf_P(
|
||||
PSTR("individual read %d: %d %d %d %d %d %d %d %d\r\n"),
|
||||
(int) valid,
|
||||
channels[0], channels[1], channels[2], channels[3],
|
||||
channels[4], channels[5], channels[6], channels[7]);
|
||||
@ -71,7 +73,6 @@ void loop (void) {
|
||||
}
|
||||
|
||||
void setup (void) {
|
||||
hal.uart0->begin(115200);
|
||||
hal.gpio->pinMode(27, GPIO_OUTPUT);
|
||||
hal.gpio->write(27, 0);
|
||||
hal.rcout->enable_mask(0x000000FF);
|
||||
@ -79,7 +80,7 @@ void setup (void) {
|
||||
/* Bottom 4 channels at 400hz (like on a quad) */
|
||||
hal.rcout->set_freq(0x0000000F, 400);
|
||||
for(int i = 0; i < 12; i++) {
|
||||
hal.uart0->printf_P(PSTR("rcout ch %d has frequency %d\r\n"),
|
||||
hal.console->printf_P(PSTR("rcout ch %d has frequency %d\r\n"),
|
||||
i, hal.rcout->get_freq(i));
|
||||
}
|
||||
/* Delay to let the user see the above printouts on the terminal */
|
||||
|
@ -103,8 +103,7 @@ static void mpu6k_read(int16_t* data) {
|
||||
}
|
||||
|
||||
static void setup() {
|
||||
hal.uart0->begin(115200);
|
||||
hal.uart0->printf_P(PSTR("Initializing MPU6000\r\n"));
|
||||
hal.console->printf_P(PSTR("Initializing MPU6000\r\n"));
|
||||
|
||||
/* Setup the barometer cs to stop it from holding the bus */
|
||||
hal.gpio->pinMode(_baro_cs_pin, GPIO_OUTPUT);
|
||||
@ -117,7 +116,8 @@ static void setup() {
|
||||
|
||||
uint8_t spcr = SPCR;
|
||||
uint8_t spsr = SPSR;
|
||||
hal.uart0->printf_P(PSTR("SPCR 0x%x, SPSR 0x%x\r\n"), (int)spcr, (int)spsr);
|
||||
hal.console->printf_P(PSTR("SPCR 0x%x, SPSR 0x%x\r\n"),
|
||||
(int)spcr, (int)spsr);
|
||||
|
||||
mpu6k_init();
|
||||
}
|
||||
@ -125,7 +125,7 @@ static void setup() {
|
||||
static void loop() {
|
||||
int16_t sensors[7];
|
||||
mpu6k_read(sensors);
|
||||
hal.uart0->printf_P(PSTR("mpu6k: %d %d %d %d %d %d %d\r\n"),
|
||||
hal.console->printf_P(PSTR("mpu6k: %d %d %d %d %d %d %d\r\n"),
|
||||
sensors[0], sensors[1], sensors[2],
|
||||
sensors[3], sensors[4], sensors[5], sensors[6]);
|
||||
hal.scheduler->delay(10);
|
||||
|
@ -22,11 +22,7 @@ const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
||||
DerivativeFilter<float,11> derivative;
|
||||
|
||||
// setup routine
|
||||
void setup()
|
||||
{
|
||||
// Open up a serial connection
|
||||
hal.uart0->begin(115200);
|
||||
}
|
||||
void setup(){}
|
||||
|
||||
static float noise(void)
|
||||
{
|
||||
|
@ -26,9 +26,6 @@ AverageFilterUInt16_Size4 _temp_filter;
|
||||
|
||||
void setup()
|
||||
{
|
||||
// Open up a serial connection
|
||||
hal.uart0->begin(115200);
|
||||
|
||||
// introduction
|
||||
hal.console->printf("ArduPilot ModeFilter library test ver 1.0\n\n");
|
||||
|
||||
|
@ -20,9 +20,6 @@ LowPassFilterFloat low_pass_filter;
|
||||
// setup routine
|
||||
void setup()
|
||||
{
|
||||
// Open up a serial connection
|
||||
hal.uart0->begin(115200);
|
||||
|
||||
// introduction
|
||||
hal.console->printf("ArduPilot LowPassFilter test ver 1.0\n\n");
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user