Hello,
I am new in Ardupilot’s source code and I am using a Pixhawk4 with the latest Arduplane master branch, currently trying to understand the debugging mechanisms. I connect to my PC using a USB.
-
Following this guide I was able to print debug messages in Mission Planner like seen below.
However I could not get the messages from ::printf(). Are they printed anywhere else? -
Following this guide I uploaded UART_test.cpp in a Pixhawk4 running the latest Arduplane firmware but now I can not connect to Mission Planner. I even tried commenting out all UART writes and ::printf(), so it is just a dummy code. I thought maybe something disrupted usb communication.Still can not connect to Mission Planner though. Below I attach the UART_test.cpp code for your reference.
/*
simple test of UART interfaces
*/
#include <AP_HAL/AP_HAL.h>
#include <stdio.h>
void setup();
void loop();
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
/*
setup one UART at 57600
*/
static void setup_uart(AP_HAL::UARTDriver *uart, const char *name)
{
if (uart == nullptr) {
// that UART doesn't exist on this platform
return;
}
uart->begin(57600);
}
void setup(void)
{
/*
start all UARTs at 57600 with default buffer sizes
*/
hal.scheduler->delay(1000); //Ensure that hal.serial(n) can be initialized
setup_uart(hal.serial(0), "SERIAL0"); // console
setup_uart(hal.serial(1), "SERIAL1"); // telemetry 1
setup_uart(hal.serial(2), "SERIAL2"); // telemetry 2
setup_uart(hal.serial(3), "SERIAL3"); // 1st GPS
setup_uart(hal.serial(4), "SERIAL4"); // 2nd GPS
}
static void test_uart(AP_HAL::UARTDriver *uart, const char *name)
{
if (uart == nullptr) {
// that UART doesn't exist on this platform
return;
}
uart->printf("Hello on UART %s at %.3f seconds\r\n",
name, (double)(AP_HAL::millis() * 0.001f));
}
void loop(void)
{
test_uart(hal.serial(0), "SERIAL0");
test_uart(hal.serial(1), "SERIAL1");
test_uart(hal.serial(2), "SERIAL2");
test_uart(hal.serial(3), "SERIAL3");
test_uart(hal.serial(4), "SERIAL4");
// also do a raw printf() on some platforms, which prints to the
// debug console
::printf("Hello on debug console at %.3f seconds\r\n", (double)(AP_HAL::millis() * 0.001f));
hal.scheduler->delay(1000);
}
AP_HAL_MAIN();