Replace use of println_P() with println()

This commit is contained in:
Lucas De Marchi 2015-10-25 17:50:51 -02:00 committed by Randy Mackay
parent a964ac38ec
commit 6f4904189b
40 changed files with 71 additions and 71 deletions

View File

@ -415,7 +415,7 @@ void Rover::Log_Read(uint16_t list_entry, uint16_t start_page, uint16_t end_page
"\nFree RAM: %u\n",
(unsigned)hal.util->available_memory());
cliSerial->println_P(HAL_BOARD_NAME);
cliSerial->println(HAL_BOARD_NAME);
DataFlash.LogReadProcess(list_entry, start_page, end_page,
FUNCTOR_BIND_MEMBER(&Rover::print_mode, void, AP_HAL::BetterStream *, uint8_t),

View File

@ -579,7 +579,7 @@ void Rover::load_parameters(void)
// save the current format version
g.format_version.set_and_save(Parameters::k_format_version);
cliSerial->println_P("done.");
cliSerial->println("done.");
} else {
unsigned long before = micros();
// Load all auto-loaded EEPROM variables

View File

@ -83,7 +83,7 @@ void Rover::read_trim_switch()
ch7_flag = false;
if (control_mode == MANUAL) {
hal.console->println_P("Erasing waypoints");
hal.console->println("Erasing waypoints");
// if SW7 is ON in MANUAL = Erase the Flight Plan
mission.clear();
if (channel_steer->control_in > 3000) {

View File

@ -153,7 +153,7 @@ void Rover::init_ardupilot()
if (g.compass_enabled==true) {
if (!compass.init()|| !compass.read()) {
cliSerial->println_P("Compass initialisation failed!");
cliSerial->println("Compass initialisation failed!");
g.compass_enabled = false;
} else {
ahrs.set_compass(&compass);
@ -198,12 +198,12 @@ void Rover::init_ardupilot()
//
if (g.cli_enabled == 1) {
const prog_char_t *msg = "\nPress ENTER 3 times to start interactive setup\n";
cliSerial->println_P(msg);
cliSerial->println(msg);
if (gcs[1].initialised && (gcs[1].get_uart() != NULL)) {
gcs[1].get_uart()->println_P(msg);
gcs[1].get_uart()->println(msg);
}
if (num_gcs > 2 && gcs[2].initialised && (gcs[2].get_uart() != NULL)) {
gcs[2].get_uart()->println_P(msg);
gcs[2].get_uart()->println(msg);
}
}
#endif

View File

@ -266,7 +266,7 @@ int8_t Rover::test_modeswitch(uint8_t argc, const Menu::arg *argv)
*/
int8_t Rover::test_logging(uint8_t argc, const Menu::arg *argv)
{
cliSerial->println_P("Testing dataflash logging");
cliSerial->println("Testing dataflash logging");
DataFlash.ShowDeviceInfo(cliSerial);
return 0;
}
@ -363,7 +363,7 @@ int8_t Rover::test_mag(uint8_t argc, const Menu::arg *argv)
}
if (!compass.init()) {
cliSerial->println_P("Compass initialisation failed!");
cliSerial->println("Compass initialisation failed!");
return 0;
}
ahrs.init();
@ -406,7 +406,7 @@ int8_t Rover::test_mag(uint8_t argc, const Menu::arg *argv)
(double)mag.x, (double)mag.y, (double)mag.z,
(double)mag_ofs.x, (double)mag_ofs.y, (double)mag_ofs.z);
} else {
cliSerial->println_P("compass not healthy");
cliSerial->println("compass not healthy");
}
counter=0;
}
@ -417,7 +417,7 @@ int8_t Rover::test_mag(uint8_t argc, const Menu::arg *argv)
// save offsets. This allows you to get sane offset values using
// the CLI before you go flying.
cliSerial->println_P("saving offsets");
cliSerial->println("saving offsets");
compass.save_offsets();
return (0);
}
@ -432,7 +432,7 @@ int8_t Rover::test_sonar(uint8_t argc, const Menu::arg *argv)
sonar.update();
if (sonar.status() == RangeFinder::RangeFinder_NotConnected) {
cliSerial->println_P("WARNING: Sonar is not enabled");
cliSerial->println("WARNING: Sonar is not enabled");
}
print_hit_enter();

View File

@ -293,7 +293,7 @@ void Tracker::load_parameters(void)
// save the current format version
g.format_version.set_and_save(Parameters::k_format_version);
hal.console->println_P("done.");
hal.console->println("done.");
} else {
uint32_t before = hal.scheduler->micros();
// Load all auto-loaded EEPROM variables

View File

@ -68,7 +68,7 @@ void Tracker::init_tracker()
if (g.compass_enabled==true) {
if (!compass.init() || !compass.read()) {
hal.console->println_P("Compass initialisation failed!");
hal.console->println("Compass initialisation failed!");
g.compass_enabled = false;
} else {
ahrs.set_compass(&compass);

View File

@ -772,7 +772,7 @@ void Copter::Log_Read(uint16_t list_entry, uint16_t start_page, uint16_t end_pag
"\nFrame: " FRAME_CONFIG_STRING "\n",
(unsigned) hal.util->available_memory());
cliSerial->println_P(HAL_BOARD_NAME);
cliSerial->println(HAL_BOARD_NAME);
DataFlash.LogReadProcess(list_entry, start_page, end_page,
FUNCTOR_BIND_MEMBER(&Copter::print_flight_mode, void, AP_HAL::BetterStream *, uint8_t),

View File

@ -1165,7 +1165,7 @@ void Copter::load_parameters(void)
// save the current format version
g.format_version.set_and_save(Parameters::k_format_version);
cliSerial->println_P("done.");
cliSerial->println("done.");
} else {
uint32_t before = micros();
// Load all auto-loaded EEPROM variables

View File

@ -87,7 +87,7 @@ void Copter::init_compass()
{
if (!compass.init() || !compass.read()) {
// make sure we don't pass a broken compass to DCM
cliSerial->println_P("COMPASS INIT ERROR");
cliSerial->println("COMPASS INIT ERROR");
Log_Write_Error(ERROR_SUBSYSTEM_COMPASS,ERROR_CODE_FAILED_TO_INITIALISE);
return;
}

View File

@ -220,12 +220,12 @@ void Copter::init_ardupilot()
#if CLI_ENABLED == ENABLED
if (g.cli_enabled) {
const prog_char_t *msg = "\nPress ENTER 3 times to start interactive setup\n";
cliSerial->println_P(msg);
cliSerial->println(msg);
if (gcs[1].initialised && (gcs[1].get_uart() != NULL)) {
gcs[1].get_uart()->println_P(msg);
gcs[1].get_uart()->println(msg);
}
if (num_gcs > 2 && gcs[2].initialised && (gcs[2].get_uart() != NULL)) {
gcs[2].get_uart()->println_P(msg);
gcs[2].get_uart()->println(msg);
}
}
#endif // CLI_ENABLED

View File

@ -44,7 +44,7 @@ int8_t Copter::test_baro(uint8_t argc, const Menu::arg *argv)
read_barometer();
if (!barometer.healthy()) {
cliSerial->println_P("not healthy");
cliSerial->println("not healthy");
} else {
cliSerial->printf_P("Alt: %0.2fm, Raw: %f Temperature: %.1f\n",
(double)(baro_alt / 100.0f),
@ -71,7 +71,7 @@ int8_t Copter::test_compass(uint8_t argc, const Menu::arg *argv)
}
if (!compass.init()) {
cliSerial->println_P("Compass initialisation failed!");
cliSerial->println("Compass initialisation failed!");
return 0;
}
@ -127,7 +127,7 @@ int8_t Copter::test_compass(uint8_t argc, const Menu::arg *argv)
(double)mag_ofs.y,
(double)mag_ofs.z);
} else {
cliSerial->println_P("compass not healthy");
cliSerial->println("compass not healthy");
}
counter=0;
}
@ -139,7 +139,7 @@ int8_t Copter::test_compass(uint8_t argc, const Menu::arg *argv)
// save offsets. This allows you to get sane offset values using
// the CLI before you go flying.
cliSerial->println_P("saving offsets");
cliSerial->println("saving offsets");
compass.save_offsets();
return (0);
}

View File

@ -24,10 +24,10 @@ MENU2(log_menu, "Log", log_menu_commands, FUNCTOR_BIND(&plane, &Plane::print_log
bool Plane::print_log_menu(void)
{
cliSerial->println_P("logs enabled: ");
cliSerial->println("logs enabled: ");
if (0 == g.log_bitmask) {
cliSerial->println_P("none");
cliSerial->println("none");
}else{
// Macro to make the following code a bit easier on the eye.
// Pass it the capitalised name of the log option, as defined
@ -508,7 +508,7 @@ void Plane::Log_Read(uint16_t list_entry, int16_t start_page, int16_t end_page)
"\nFree RAM: %u\n",
(unsigned)hal.util->available_memory());
cliSerial->println_P(HAL_BOARD_NAME);
cliSerial->println(HAL_BOARD_NAME);
DataFlash.LogReadProcess(list_entry, start_page, end_page,
FUNCTOR_BIND_MEMBER(&Plane::print_flight_mode, void, AP_HAL::BetterStream *, uint8_t),

View File

@ -1271,7 +1271,7 @@ void Plane::load_parameters(void)
// save the current format version
g.format_version.set_and_save(Parameters::k_format_version);
cliSerial->println_P("done.");
cliSerial->println("done.");
} else {
uint32_t before = micros();
// Load all auto-loaded EEPROM variables

View File

@ -183,7 +183,7 @@ void Plane::init_ardupilot()
compass_ok = true;
#endif
if (!compass_ok) {
cliSerial->println_P("Compass initialisation failed!");
cliSerial->println("Compass initialisation failed!");
g.compass_enabled = false;
} else {
ahrs.set_compass(&compass);
@ -229,12 +229,12 @@ void Plane::init_ardupilot()
#if CLI_ENABLED == ENABLED
if (g.cli_enabled == 1) {
const prog_char_t *msg = "\nPress ENTER 3 times to start interactive setup\n";
cliSerial->println_P(msg);
cliSerial->println(msg);
if (gcs[1].initialised && (gcs[1].get_uart() != NULL)) {
gcs[1].get_uart()->println_P(msg);
gcs[1].get_uart()->println(msg);
}
if (num_gcs > 2 && gcs[2].initialised && (gcs[2].get_uart() != NULL)) {
gcs[2].get_uart()->println_P(msg);
gcs[2].get_uart()->println(msg);
}
}
#endif // CLI_ENABLED

View File

@ -425,7 +425,7 @@ int8_t Plane::test_mag(uint8_t argc, const Menu::arg *argv)
}
if (!compass.init()) {
cliSerial->println_P("Compass initialisation failed!");
cliSerial->println("Compass initialisation failed!");
return 0;
}
ahrs.init();
@ -470,7 +470,7 @@ int8_t Plane::test_mag(uint8_t argc, const Menu::arg *argv)
(double)mag.x, (double)mag.y, (double)mag.z,
(double)mag_ofs.x, (double)mag_ofs.y, (double)mag_ofs.z);
} else {
cliSerial->println_P("compass not healthy");
cliSerial->println("compass not healthy");
}
counter=0;
}
@ -482,7 +482,7 @@ int8_t Plane::test_mag(uint8_t argc, const Menu::arg *argv)
// save offsets. This allows you to get sane offset values using
// the CLI before you go flying.
cliSerial->println_P("saving offsets");
cliSerial->println("saving offsets");
compass.save_offsets();
return (0);
}
@ -527,7 +527,7 @@ int8_t Plane::test_pressure(uint8_t argc, const Menu::arg *argv)
barometer.update();
if (!barometer.healthy()) {
cliSerial->println_P("not healthy");
cliSerial->println("not healthy");
} else {
cliSerial->printf_P("Alt: %0.2fm, Raw: %f Temperature: %.1f\n",
(double)barometer.get_altitude(),

View File

@ -11,7 +11,7 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();
void setup()
{
hal.console->println_P("hello world");
hal.console->println("hello world");
}
void loop()

View File

@ -195,7 +195,7 @@ void AP_Airspeed::calibrate(bool in_startup)
}
if (count == 0) {
// unhealthy sensor
hal.console->println_P("Airspeed sensor unhealthy");
hal.console->println("Airspeed sensor unhealthy");
_offset.set(0);
return;
}

View File

@ -239,7 +239,7 @@ bool AP_Compass_LSM303D::_data_ready()
bool AP_Compass_LSM303D::_read_raw()
{
if (_register_read(ADDR_CTRL_REG7) != _reg7_expected) {
hal.console->println_P(
hal.console->println(
"LSM303D _read_data_transaction_accel: _reg7_expected unexpected");
// reset();
return false;
@ -318,7 +318,7 @@ AP_Compass_LSM303D::init()
_spi_sem->give();
break;
} else {
hal.console->println_P(
hal.console->println(
"LSM303D startup failed: no data ready");
}
_spi_sem->give();

View File

@ -451,7 +451,7 @@ void Compass::_detect_backends(void)
if (_backend_count == 0 ||
_compass_count == 0) {
hal.console->println_P("No Compass backends available");
hal.console->println("No Compass backends available");
}
}

View File

@ -83,7 +83,7 @@ T AP_Curve<T,SIZE>::get_y( T x )
template <class T, uint8_t SIZE>
void AP_Curve<T,SIZE>::dump_curve(AP_HAL::BetterStream* s)
{
s->println_P("Curve:");
s->println("Curve:");
for( uint8_t i = 0; i<_num_points; i++ ){
s->print("x:");
s->print(_x[i]);

View File

@ -4,7 +4,7 @@
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
void setup(void) {
hal.console->println_P("Starting Printf test");
hal.console->println("Starting Printf test");
}
static const struct {

View File

@ -247,7 +247,7 @@ void FLYMAPLEScheduler::panic(const prog_char_t *errormsg, ...) {
}
void FLYMAPLEScheduler::reboot(bool hold_in_bootloader) {
hal.uartA->println_P("GOING DOWN FOR A REBOOT\r\n");
hal.uartA->println("GOING DOWN FOR A REBOOT\r\n");
hal.scheduler->delay(100);
nvic_sys_reset();
}

View File

@ -29,7 +29,7 @@ void setup(void)
hal.console->println(1000, 8);
hal.console->println(1000, 10);
hal.console->println(1000, 16);
hal.console->println_P("progmem");
hal.console->println("progmem");
hal.console->printf("printf %d %u %#x %p %f %S\n", -1000, 1000, 1000, 1000, 1.2345, "progmem");
hal.console->printf_P("printf_P %d %u %#x %p %f %S\n", -1000, 1000, 1000, 1000, 1.2345, "progmem");

View File

@ -30,7 +30,7 @@ void setup(void)
hal.uartA->println(1000, 8);
hal.uartA->println(1000, 10);
hal.uartA->println(1000, 16);
hal.uartA->println_P("progmem");
hal.uartA->println("progmem");
int x = 3;
int *ptr = &x;
hal.uartA->printf("printf %d %u %#x %p %f %s\n", -1000, 1000, 1000, ptr, 1.2345, "progmem");

View File

@ -10,11 +10,11 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();
void setup() {
hal.scheduler->delay(5000);
hal.console->println_P("Empty setup");
hal.console->println("Empty setup");
}
void loop()
{
hal.console->println_P("loop");
hal.console->println("loop");
hal.console->printf("hello %d\n", 1234);
hal.scheduler->delay(1000);
}

View File

@ -380,7 +380,7 @@ void RCOutput_Bebop::_run_rcout()
pthread_mutex_lock(&_mutex);
ret = clock_gettime(CLOCK_MONOTONIC, &ts);
if (ret != 0)
hal.console->println_P("RCOutput_Bebop: bad checksum in obs data");
hal.console->println("RCOutput_Bebop: bad checksum in obs data");
if (ts.tv_nsec > (1000000000 - BEBOP_BLDC_TIMEOUT_NS))
{

View File

@ -10,7 +10,7 @@
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
void setup() {
hal.console->println_P("hello world");
hal.console->println("hello world");
}
void loop()

View File

@ -189,14 +189,14 @@ void SITLScheduler::system_initialized() {
void SITLScheduler::sitl_end_atomic() {
if (_nested_atomic_ctr == 0)
hal.uartA->println_P("NESTED ATOMIC ERROR");
hal.uartA->println("NESTED ATOMIC ERROR");
else
_nested_atomic_ctr--;
}
void SITLScheduler::reboot(bool hold_in_bootloader)
{
hal.uartA->println_P("REBOOT NOT IMPLEMENTED\r\n");
hal.uartA->println("REBOOT NOT IMPLEMENTED\r\n");
}
void SITLScheduler::_run_timer_procs(bool called_from_isr)

View File

@ -538,7 +538,7 @@ bool AP_InertialSensor::_calculate_trim(const Vector3f &accel_sample, float& tri
trim_roll = atan2f(-accel_sample.y, -accel_sample.z);
if (fabsf(trim_roll) > radians(10) ||
fabsf(trim_pitch) > radians(10)) {
hal.console->println_P("trim over maximum of 10 degrees");
hal.console->println("trim over maximum of 10 degrees");
return false;
}
hal.console->printf_P("Trim OK: roll=%.2f pitch=%.2f\n",

View File

@ -803,8 +803,8 @@ void AP_InertialSensor_LSM9DS0::_set_gyro_filter(uint8_t filter_hz)
/* dump all config registers - used for debug */
void AP_InertialSensor_LSM9DS0::_dump_registers(void)
{
hal.console->println_P("LSM9DS0 registers:");
hal.console->println_P("Gyroscope registers:");
hal.console->println("LSM9DS0 registers:");
hal.console->println("Gyroscope registers:");
const uint8_t first = OUT_TEMP_L_XM;
const uint8_t last = ACT_DUR;
for (uint8_t reg=first; reg<=last; reg++) {
@ -816,7 +816,7 @@ void AP_InertialSensor_LSM9DS0::_dump_registers(void)
}
hal.console->println();
hal.console->println_P("Accelerometer and Magnetometers registers:");
hal.console->println("Accelerometer and Magnetometers registers:");
for (uint8_t reg=first; reg<=last; reg++) {
uint8_t v = _register_read_xm(reg);
hal.console->printf_P("%02x:%02x ", (unsigned)reg, (unsigned)v);

View File

@ -848,7 +848,7 @@ bool AP_InertialSensor_MPU6000::_hardware_init(void)
#endif
}
if (tries == 5) {
hal.console->println_P("Failed to boot MPU6000 5 times");
hal.console->println("Failed to boot MPU6000 5 times");
goto fail_tries;
}
@ -867,7 +867,7 @@ fail_tries:
// dump all config registers - used for debug
void AP_InertialSensor_MPU6000::_dump_registers(void)
{
hal.console->println_P("MPU6000 registers");
hal.console->println("MPU6000 registers");
if (_bus_sem->take(100)) {
for (uint8_t reg=MPUREG_PRODUCT_ID; reg<=108; reg++) {
uint8_t v = _register_read(reg);
@ -921,7 +921,7 @@ int AP_MPU6000_AuxiliaryBusSlave::passthrough_read(uint8_t reg, uint8_t *buf,
assert(buf);
if (_registered) {
hal.console->println_P("Error: can't passthrough when slave is already configured");
hal.console->println("Error: can't passthrough when slave is already configured");
return -1;
}
@ -944,7 +944,7 @@ int AP_MPU6000_AuxiliaryBusSlave::passthrough_read(uint8_t reg, uint8_t *buf,
int AP_MPU6000_AuxiliaryBusSlave::passthrough_write(uint8_t reg, uint8_t val)
{
if (_registered) {
hal.console->println_P("Error: can't passthrough when slave is already configured");
hal.console->println("Error: can't passthrough when slave is already configured");
return -1;
}
@ -966,7 +966,7 @@ int AP_MPU6000_AuxiliaryBusSlave::passthrough_write(uint8_t reg, uint8_t val)
int AP_MPU6000_AuxiliaryBusSlave::read(uint8_t *buf)
{
if (!_registered) {
hal.console->println_P("Error: can't read before configuring slave");
hal.console->println("Error: can't read before configuring slave");
return -1;
}

View File

@ -281,7 +281,7 @@ bool AP_InertialSensor_MPU9250::initialize_driver_state(AP_HAL::SPIDeviceDriver
}
if (tries == 5) {
hal.console->println_P("Failed to boot MPU9250 5 times");
hal.console->println("Failed to boot MPU9250 5 times");
goto fail_tries;
}
@ -528,7 +528,7 @@ bool AP_InertialSensor_MPU9250::_hardware_init(void)
// dump all config registers - used for debug
void AP_InertialSensor_MPU9250::_dump_registers(AP_HAL::SPIDeviceDriver *spi)
{
hal.console->println_P("MPU9250 registers");
hal.console->println("MPU9250 registers");
for (uint8_t reg=0; reg<=126; reg++) {
uint8_t v = _register_read(spi, reg);
hal.console->printf_P("%02x:%02x ", (unsigned)reg, (unsigned)v);

View File

@ -34,7 +34,7 @@ bool AP_InertialSensor_UserInteract_MAVLink::blocking_read(void)
return true;
}
}
hal.console->println_P("Timed out waiting for user response");
hal.console->println("Timed out waiting for user response");
_gcs->set_snoop(NULL);
return false;
}

View File

@ -43,7 +43,7 @@ void loop(void)
int16_t user_input;
hal.console->println();
hal.console->println_P(
hal.console->println(
"Menu:\r\n"
" c calibrate accelerometers\r\n"
" d) display offsets and scaling\r\n"

View File

@ -23,7 +23,7 @@ static void test_rotation_accuracy(void)
int16_t i;
float rot_angle;
hal.console->println_P("\nRotation method accuracy:");
hal.console->println("\nRotation method accuracy:");
for( i=0; i<90; i++ ) {

View File

@ -157,7 +157,7 @@ Menu::_run_command(bool prompt_on_enter)
if (cmd_found==false)
{
_port->println_P("Invalid command, type 'help'");
_port->println("Invalid command, type 'help'");
}
return false;
@ -228,7 +228,7 @@ Menu::_help(void)
{
int i;
_port->println_P("Commands:");
_port->println("Commands:");
for (i = 0; i < _entries; i++) {
hal.scheduler->delay(10);
_port->printf_P(" %S\n", _commands[i].command);

View File

@ -32,7 +32,7 @@
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
void setup () {
hal.console->println_P("Unit test for AP_Mount. This sketch"
hal.console->println("Unit test for AP_Mount. This sketch"
"has no functionality, it only tests build.");
}
void loop () {}

View File

@ -739,7 +739,7 @@ bool AP_Param::save(bool force_save)
if (ofs+type_size((enum ap_var_type)phdr.type)+2*sizeof(phdr) >= _storage.size()) {
// we are out of room for saving variables
hal.console->println_P("EEPROM full");
hal.console->println("EEPROM full");
return false;
}

View File

@ -563,7 +563,7 @@ void DataFlash_Block::DumpPageInfo(AP_HAL::BetterStream *port)
void DataFlash_Block::ShowDeviceInfo(AP_HAL::BetterStream *port)
{
if (!CardInserted()) {
port->println_P("No dataflash inserted");
port->println("No dataflash inserted");
return;
}
ReadManufacturerID();