From a964ac38ece2991cb92b811109f2ac1cc93a6318 Mon Sep 17 00:00:00 2001 From: Lucas De Marchi Date: Sun, 25 Oct 2015 17:22:31 -0200 Subject: [PATCH] Replace use of print_P() with print() --- APMrover2/system.cpp | 12 +- ArduCopter/flight_mode.cpp | 32 ++--- ArduCopter/setup.cpp | 16 +-- ArduCopter/system.cpp | 2 +- ArduPlane/system.cpp | 28 ++-- ArduPlane/test.cpp | 2 +- libraries/AP_Curve/AP_Curve.cpp | 6 +- libraries/AP_GPS/AP_GPS.cpp | 18 +-- libraries/AP_HAL_FLYMAPLE/AnalogIn.cpp | 2 +- .../AP_InertialSensor/AP_InertialSensor.cpp | 4 +- .../AP_Mission_test/AP_Mission_test.cpp | 134 +++++++++--------- .../ToshibaLED_test/ToshibaLED_test.cpp | 8 +- .../AP_PerfMon_test/AP_PerfMon_test.cpp | 2 +- 13 files changed, 133 insertions(+), 133 deletions(-) diff --git a/APMrover2/system.cpp b/APMrover2/system.cpp index c767e94dfa..98ec51edd1 100644 --- a/APMrover2/system.cpp +++ b/APMrover2/system.cpp @@ -450,22 +450,22 @@ void Rover::print_mode(AP_HAL::BetterStream *port, uint8_t mode) { switch (mode) { case MANUAL: - port->print_P("Manual"); + port->print("Manual"); break; case HOLD: - port->print_P("HOLD"); + port->print("HOLD"); break; case LEARNING: - port->print_P("Learning"); + port->print("Learning"); break; case STEERING: - port->print_P("Steering"); + port->print("Steering"); break; case AUTO: - port->print_P("AUTO"); + port->print("AUTO"); break; case RTL: - port->print_P("RTL"); + port->print("RTL"); break; default: port->printf_P("Mode(%u)", (unsigned)mode); diff --git a/ArduCopter/flight_mode.cpp b/ArduCopter/flight_mode.cpp index 4e60a426d2..2cb91b3069 100644 --- a/ArduCopter/flight_mode.cpp +++ b/ArduCopter/flight_mode.cpp @@ -315,52 +315,52 @@ void Copter::print_flight_mode(AP_HAL::BetterStream *port, uint8_t mode) { switch (mode) { case STABILIZE: - port->print_P("STABILIZE"); + port->print("STABILIZE"); break; case ACRO: - port->print_P("ACRO"); + port->print("ACRO"); break; case ALT_HOLD: - port->print_P("ALT_HOLD"); + port->print("ALT_HOLD"); break; case AUTO: - port->print_P("AUTO"); + port->print("AUTO"); break; case GUIDED: - port->print_P("GUIDED"); + port->print("GUIDED"); break; case LOITER: - port->print_P("LOITER"); + port->print("LOITER"); break; case RTL: - port->print_P("RTL"); + port->print("RTL"); break; case CIRCLE: - port->print_P("CIRCLE"); + port->print("CIRCLE"); break; case LAND: - port->print_P("LAND"); + port->print("LAND"); break; case OF_LOITER: - port->print_P("OF_LOITER"); + port->print("OF_LOITER"); break; case DRIFT: - port->print_P("DRIFT"); + port->print("DRIFT"); break; case SPORT: - port->print_P("SPORT"); + port->print("SPORT"); break; case FLIP: - port->print_P("FLIP"); + port->print("FLIP"); break; case AUTOTUNE: - port->print_P("AUTOTUNE"); + port->print("AUTOTUNE"); break; case POSHOLD: - port->print_P("POSHOLD"); + port->print("POSHOLD"); break; case BRAKE: - port->print_P("BRAKE"); + port->print("BRAKE"); break; default: port->printf_P("Mode(%u)", (unsigned)mode); diff --git a/ArduCopter/setup.cpp b/ArduCopter/setup.cpp index 553b517a5d..587755b9f9 100644 --- a/ArduCopter/setup.cpp +++ b/ArduCopter/setup.cpp @@ -460,15 +460,15 @@ void Copter::report_compass() } // motor compensation - cliSerial->print_P("Motor Comp: "); + cliSerial->print("Motor Comp: "); if( compass.get_motor_compensation_type() == AP_COMPASS_MOT_COMP_DISABLED ) { - cliSerial->print_P("Off\n"); + cliSerial->print("Off\n"); }else{ if( compass.get_motor_compensation_type() == AP_COMPASS_MOT_COMP_THROTTLE ) { - cliSerial->print_P("Throttle"); + cliSerial->print("Throttle"); } if( compass.get_motor_compensation_type() == AP_COMPASS_MOT_COMP_CURRENT ) { - cliSerial->print_P("Current"); + cliSerial->print("Current"); } Vector3f motor_compensation; for (uint8_t i=0; iprint_P("-"); + cliSerial->print("-"); } cliSerial->println(); } @@ -502,10 +502,10 @@ void Copter::print_divider(void) void Copter::print_enabled(bool b) { if(b) - cliSerial->print_P("en"); + cliSerial->print("en"); else - cliSerial->print_P("dis"); - cliSerial->print_P("abled\n"); + cliSerial->print("dis"); + cliSerial->print("abled\n"); } void Copter::report_version() diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index bc90a0e667..d82beb9fcf 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -282,7 +282,7 @@ void Copter::init_ardupilot() // init vehicle capabilties init_capabilities(); - cliSerial->print_P("\nReady to FLY "); + cliSerial->print("\nReady to FLY "); // flag that initialisation has completed ap.initialised = true; diff --git a/ArduPlane/system.cpp b/ArduPlane/system.cpp index 587efc0283..7b33d3963e 100644 --- a/ArduPlane/system.cpp +++ b/ArduPlane/system.cpp @@ -636,43 +636,43 @@ void Plane::print_flight_mode(AP_HAL::BetterStream *port, uint8_t mode) { switch (mode) { case MANUAL: - port->print_P("Manual"); + port->print("Manual"); break; case CIRCLE: - port->print_P("Circle"); + port->print("Circle"); break; case STABILIZE: - port->print_P("Stabilize"); + port->print("Stabilize"); break; case TRAINING: - port->print_P("Training"); + port->print("Training"); break; case ACRO: - port->print_P("ACRO"); + port->print("ACRO"); break; case FLY_BY_WIRE_A: - port->print_P("FBW_A"); + port->print("FBW_A"); break; case AUTOTUNE: - port->print_P("AUTOTUNE"); + port->print("AUTOTUNE"); break; case FLY_BY_WIRE_B: - port->print_P("FBW_B"); + port->print("FBW_B"); break; case CRUISE: - port->print_P("CRUISE"); + port->print("CRUISE"); break; case AUTO: - port->print_P("AUTO"); + port->print("AUTO"); break; case RTL: - port->print_P("RTL"); + port->print("RTL"); break; case LOITER: - port->print_P("Loiter"); + port->print("Loiter"); break; case GUIDED: - port->print_P("Guided"); + port->print("Guided"); break; default: port->printf_P("Mode(%u)", (unsigned)mode); @@ -683,7 +683,7 @@ void Plane::print_flight_mode(AP_HAL::BetterStream *port, uint8_t mode) #if CLI_ENABLED == ENABLED void Plane::print_comma(void) { - cliSerial->print_P(","); + cliSerial->print(","); } #endif diff --git a/ArduPlane/test.cpp b/ArduPlane/test.cpp index a69f14e03f..f871355ca8 100644 --- a/ArduPlane/test.cpp +++ b/ArduPlane/test.cpp @@ -89,7 +89,7 @@ int8_t Plane::test_passthru(uint8_t argc, const Menu::arg *argv) // New radio frame? (we could use also if((millis()- timer) > 20) if (hal.rcin->new_input()) { - cliSerial->print_P("CH:"); + cliSerial->print("CH:"); for(int16_t i = 0; i < 8; i++) { cliSerial->print(hal.rcin->read(i)); // Print channel values print_comma(); diff --git a/libraries/AP_Curve/AP_Curve.cpp b/libraries/AP_Curve/AP_Curve.cpp index 8a739c0897..e34a13b874 100644 --- a/libraries/AP_Curve/AP_Curve.cpp +++ b/libraries/AP_Curve/AP_Curve.cpp @@ -85,11 +85,11 @@ void AP_Curve::dump_curve(AP_HAL::BetterStream* s) { s->println_P("Curve:"); for( uint8_t i = 0; i<_num_points; i++ ){ - s->print_P("x:"); + s->print("x:"); s->print(_x[i]); - s->print_P("\ty:"); + s->print("\ty:"); s->print(_y[i]); - s->print_P("\tslope:"); + s->print("\tslope:"); s->print(_slope[i],4); s->println(); } diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index 7d3e1bb652..c34ebc3762 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -200,7 +200,7 @@ AP_GPS::detect_instance(uint8_t instance) if (_type[instance] == GPS_TYPE_PX4) { // check for explicitely chosen PX4 GPS beforehand // it is not possible to autodetect it, nor does it require a real UART - hal.console->print_P(" PX4 "); + hal.console->print(" PX4 "); new_gps = new AP_GPS_PX4(*this, state[instance], _port[instance]); goto found_gps; } @@ -218,10 +218,10 @@ AP_GPS::detect_instance(uint8_t instance) #if GPS_RTK_AVAILABLE // by default the sbf/trimble gps outputs no data on its port, until configured. if (_type[instance] == GPS_TYPE_SBF) { - hal.console->print_P(" SBF "); + hal.console->print(" SBF "); new_gps = new AP_GPS_SBF(*this, state[instance], _port[instance]); } else if ((_type[instance] == GPS_TYPE_GSOF)) { - hal.console->print_P(" GSOF "); + hal.console->print(" GSOF "); new_gps = new AP_GPS_GSOF(*this, state[instance], _port[instance]); } #endif // GPS_RTK_AVAILABLE @@ -265,23 +265,23 @@ AP_GPS::detect_instance(uint8_t instance) if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_UBLOX) && pgm_read_dword(&_baudrates[dstate->last_baud]) >= 38400 && AP_GPS_UBLOX::_detect(dstate->ublox_detect_state, data)) { - hal.console->print_P(" ublox "); + hal.console->print(" ublox "); new_gps = new AP_GPS_UBLOX(*this, state[instance], _port[instance]); } else if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_MTK19) && AP_GPS_MTK19::_detect(dstate->mtk19_detect_state, data)) { - hal.console->print_P(" MTK19 "); + hal.console->print(" MTK19 "); new_gps = new AP_GPS_MTK19(*this, state[instance], _port[instance]); } else if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_MTK) && AP_GPS_MTK::_detect(dstate->mtk_detect_state, data)) { - hal.console->print_P(" MTK "); + hal.console->print(" MTK "); new_gps = new AP_GPS_MTK(*this, state[instance], _port[instance]); } #if GPS_RTK_AVAILABLE else if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_SBP) && AP_GPS_SBP::_detect(dstate->sbp_detect_state, data)) { - hal.console->print_P(" SBP "); + hal.console->print(" SBP "); new_gps = new AP_GPS_SBP(*this, state[instance], _port[instance]); } #endif // HAL_CPU_CLASS @@ -289,7 +289,7 @@ AP_GPS::detect_instance(uint8_t instance) // save a bit of code space on a 1280 else if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_SIRF) && AP_GPS_SIRF::_detect(dstate->sirf_detect_state, data)) { - hal.console->print_P(" SIRF "); + hal.console->print(" SIRF "); new_gps = new AP_GPS_SIRF(*this, state[instance], _port[instance]); } else if (now - dstate->detect_started_ms > (ARRAY_SIZE(_baudrates) * GPS_BAUD_TIME_MS)) { @@ -297,7 +297,7 @@ AP_GPS::detect_instance(uint8_t instance) // a MTK or UBLOX which has booted in NMEA mode if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_NMEA) && AP_GPS_NMEA::_detect(dstate->nmea_detect_state, data)) { - hal.console->print_P(" NMEA "); + hal.console->print(" NMEA "); new_gps = new AP_GPS_NMEA(*this, state[instance], _port[instance]); } } diff --git a/libraries/AP_HAL_FLYMAPLE/AnalogIn.cpp b/libraries/AP_HAL_FLYMAPLE/AnalogIn.cpp index 81a470c724..61a8aac2bd 100644 --- a/libraries/AP_HAL_FLYMAPLE/AnalogIn.cpp +++ b/libraries/AP_HAL_FLYMAPLE/AnalogIn.cpp @@ -52,7 +52,7 @@ FLYMAPLEAnalogSource* FLYMAPLEAnalogIn::_create_channel(int16_t chnum) { void FLYMAPLEAnalogIn::_register_channel(FLYMAPLEAnalogSource* ch) { if (_num_channels >= FLYMAPLE_INPUT_MAX_CHANNELS) { for(;;) { - hal.console->print_P( + hal.console->print( "Error: AP_HAL_FLYMAPLE::FLYMAPLEAnalogIn out of channels\r\n"); hal.scheduler->delay(1000); } diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.cpp b/libraries/AP_InertialSensor/AP_InertialSensor.cpp index 8439c6a84b..9a532f6a89 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor.cpp @@ -922,7 +922,7 @@ AP_InertialSensor::_init_gyro() AP_Notify::flags.initialising = true; // cold start - hal.console->print_P("Init Gyro"); + hal.console->print("Init Gyro"); /* we do the gyro calibration with no board rotation. This avoids @@ -961,7 +961,7 @@ AP_InertialSensor::_init_gyro() memset(diff_norm, 0, sizeof(diff_norm)); - hal.console->print_P("*"); + hal.console->print("*"); for (uint8_t k=0; kprint_P("\nMission Complete!\n"); + hal.console->print("\nMission Complete!\n"); } // run_mission_test - tests the stop and resume feature @@ -149,7 +149,7 @@ void MissionTest::run_mission_test() print_mission(); // start mission - hal.console->print_P("\nRunning missions\n"); + hal.console->print("\nRunning missions\n"); mission.start(); // update mission forever @@ -174,7 +174,7 @@ void MissionTest::init_mission() cmd.content.location.lat = 12345678; cmd.content.location.lng = 23456789; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #1 : take-off to 10m @@ -185,7 +185,7 @@ void MissionTest::init_mission() cmd.content.location.lat = 0; cmd.content.location.lng = 0; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #2 : first waypoint @@ -196,7 +196,7 @@ void MissionTest::init_mission() cmd.content.location.lat = 12345678; cmd.content.location.lng = 23456789; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #3 : second waypoint @@ -206,7 +206,7 @@ void MissionTest::init_mission() cmd.content.location.lng = -1234567890; cmd.content.location.alt = 22; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #4 : do-jump to first waypoint 3 times @@ -214,7 +214,7 @@ void MissionTest::init_mission() cmd.content.jump.target = 2; cmd.content.jump.num_times = 1; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #5 : RTL @@ -224,7 +224,7 @@ void MissionTest::init_mission() cmd.content.location.lng = 0; cmd.content.location.alt = 0; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } } @@ -245,7 +245,7 @@ void MissionTest::init_mission_no_nav_commands() cmd.content.location.lat = 12345678; cmd.content.location.lng = 23456789; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #1 : "do" command @@ -256,7 +256,7 @@ void MissionTest::init_mission_no_nav_commands() cmd.content.location.lat = 12345678; cmd.content.location.lng = 23456789; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #2 : "do" command @@ -267,13 +267,13 @@ void MissionTest::init_mission_no_nav_commands() cmd.content.location.lat = 0; cmd.content.location.lng = 0; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #3 : "do" command cmd.id = MAV_CMD_DO_SET_SERVO; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #4 : do-jump to first command 3 times @@ -281,7 +281,7 @@ void MissionTest::init_mission_no_nav_commands() cmd.content.jump.target = 1; cmd.content.jump.num_times = 1; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } } @@ -302,7 +302,7 @@ void MissionTest::init_mission_endless_loop() cmd.content.location.lat = 12345678; cmd.content.location.lng = 23456789; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #1 : do-jump command to itself @@ -310,7 +310,7 @@ void MissionTest::init_mission_endless_loop() cmd.content.jump.target = 1; cmd.content.jump.num_times = 2; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #2 : take-off to 10m @@ -321,7 +321,7 @@ void MissionTest::init_mission_endless_loop() cmd.content.location.lat = 0; cmd.content.location.lng = 0; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #3 : waypoint @@ -332,7 +332,7 @@ void MissionTest::init_mission_endless_loop() cmd.content.location.lat = 12345678; cmd.content.location.lng = 23456789; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } } @@ -354,7 +354,7 @@ void MissionTest::init_mission_jump_to_nonnav() cmd.content.location.lat = 12345678; cmd.content.location.lng = 23456789; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #1 : take-off to 10m @@ -365,7 +365,7 @@ void MissionTest::init_mission_jump_to_nonnav() cmd.content.location.lat = 0; cmd.content.location.lng = 0; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #2 : do-roi command @@ -376,7 +376,7 @@ void MissionTest::init_mission_jump_to_nonnav() cmd.content.location.lat = 12345678; cmd.content.location.lng = 23456789; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #3 : do-jump command to #2 @@ -384,7 +384,7 @@ void MissionTest::init_mission_jump_to_nonnav() cmd.content.jump.target = 2; cmd.content.jump.num_times = 2; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #4 : waypoint @@ -395,7 +395,7 @@ void MissionTest::init_mission_jump_to_nonnav() cmd.content.location.lat = 12345678; cmd.content.location.lng = 23456789; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } } @@ -418,7 +418,7 @@ void MissionTest::init_mission_starts_with_do_commands() cmd.content.location.lat = 12345678; cmd.content.location.lng = 23456789; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #1 : First "do" command @@ -429,7 +429,7 @@ void MissionTest::init_mission_starts_with_do_commands() cmd.content.location.lat = 12345678; cmd.content.location.lng = 23456789; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #2 : Second "do" command @@ -440,7 +440,7 @@ void MissionTest::init_mission_starts_with_do_commands() cmd.content.location.lat = 0; cmd.content.location.lng = 0; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #3 : take-off to 10m @@ -451,7 +451,7 @@ void MissionTest::init_mission_starts_with_do_commands() cmd.content.location.lat = 0; cmd.content.location.lng = 0; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #4 : Third "do" command @@ -462,7 +462,7 @@ void MissionTest::init_mission_starts_with_do_commands() cmd.content.location.lat = 12345678; cmd.content.location.lng = 23456789; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #5 : waypoint @@ -473,7 +473,7 @@ void MissionTest::init_mission_starts_with_do_commands() cmd.content.location.lat = 12345678; cmd.content.location.lng = 23456789; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } } @@ -495,7 +495,7 @@ void MissionTest::init_mission_ends_with_do_commands() cmd.content.location.lat = 12345678; cmd.content.location.lng = 23456789; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #1 : take-off to 10m @@ -506,7 +506,7 @@ void MissionTest::init_mission_ends_with_do_commands() cmd.content.location.lat = 0; cmd.content.location.lng = 0; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #2 : "do" command @@ -517,7 +517,7 @@ void MissionTest::init_mission_ends_with_do_commands() cmd.content.location.lat = 12345678; cmd.content.location.lng = 23456789; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #3 : waypoint @@ -528,7 +528,7 @@ void MissionTest::init_mission_ends_with_do_commands() cmd.content.location.lat = 12345678; cmd.content.location.lng = 23456789; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #4 : "do" command after last nav command (but not at end of mission) @@ -539,7 +539,7 @@ void MissionTest::init_mission_ends_with_do_commands() cmd.content.location.lat = 0; cmd.content.location.lng = 0; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #5 : "do" command at end of mission @@ -550,7 +550,7 @@ void MissionTest::init_mission_ends_with_do_commands() cmd.content.location.lat = 12345678; cmd.content.location.lng = 23456789; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } } @@ -571,7 +571,7 @@ void MissionTest::init_mission_ends_with_jump_command() cmd.content.location.lat = 12345678; cmd.content.location.lng = 23456789; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #1 : take-off to 10m @@ -582,7 +582,7 @@ void MissionTest::init_mission_ends_with_jump_command() cmd.content.location.lat = 0; cmd.content.location.lng = 0; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #2 : "do" command @@ -593,7 +593,7 @@ void MissionTest::init_mission_ends_with_jump_command() cmd.content.location.lat = 12345678; cmd.content.location.lng = 23456789; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #3 : waypoint @@ -604,7 +604,7 @@ void MissionTest::init_mission_ends_with_jump_command() cmd.content.location.lat = 12345678; cmd.content.location.lng = 23456789; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #4 : "do" command after last nav command (but not at end of mission) @@ -615,7 +615,7 @@ void MissionTest::init_mission_ends_with_jump_command() cmd.content.location.lat = 0; cmd.content.location.lng = 0; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #5 : "do" command at end of mission @@ -626,7 +626,7 @@ void MissionTest::init_mission_ends_with_jump_command() cmd.content.location.lat = 12345678; cmd.content.location.lng = 23456789; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #6 : do-jump command to #2 two times @@ -634,7 +634,7 @@ void MissionTest::init_mission_ends_with_jump_command() cmd.content.jump.target = 3; cmd.content.jump.num_times = 2; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } } @@ -692,7 +692,7 @@ void MissionTest::run_resume_test() cmd.content.location.lat = 12345678; cmd.content.location.lng = 23456789; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #1 : take-off to 10m @@ -703,7 +703,7 @@ void MissionTest::run_resume_test() cmd.content.location.lat = 0; cmd.content.location.lng = 0; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #2 : first waypoint @@ -714,7 +714,7 @@ void MissionTest::run_resume_test() cmd.content.location.lat = 12345678; cmd.content.location.lng = 23456789; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #3 : second waypoint @@ -724,7 +724,7 @@ void MissionTest::run_resume_test() cmd.content.location.lng = -1234567890; cmd.content.location.alt = 22; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #4 : do command @@ -735,7 +735,7 @@ void MissionTest::run_resume_test() cmd.content.location.lat = 12345678; cmd.content.location.lng = 23456789; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #5 : RTL @@ -745,7 +745,7 @@ void MissionTest::run_resume_test() cmd.content.location.lng = 0; cmd.content.location.alt = 0; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // print current mission @@ -798,7 +798,7 @@ void MissionTest::run_set_current_cmd_test() cmd.content.location.lat = 12345678; cmd.content.location.lng = 23456789; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #1 : take-off to 10m @@ -809,7 +809,7 @@ void MissionTest::run_set_current_cmd_test() cmd.content.location.lat = 0; cmd.content.location.lng = 0; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #2 : do command @@ -820,7 +820,7 @@ void MissionTest::run_set_current_cmd_test() cmd.content.location.lat = 12345678; cmd.content.location.lng = 23456789; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #3 : first waypoint @@ -831,7 +831,7 @@ void MissionTest::run_set_current_cmd_test() cmd.content.location.lat = 12345678; cmd.content.location.lng = 23456789; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #4 : second waypoint @@ -841,7 +841,7 @@ void MissionTest::run_set_current_cmd_test() cmd.content.location.lng = -1234567890; cmd.content.location.alt = 22; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #5 : do command @@ -852,7 +852,7 @@ void MissionTest::run_set_current_cmd_test() cmd.content.location.lat = 12345678; cmd.content.location.lng = 23456789; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #6 : RTL @@ -862,7 +862,7 @@ void MissionTest::run_set_current_cmd_test() cmd.content.location.lng = 0; cmd.content.location.alt = 0; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // print current mission @@ -903,7 +903,7 @@ void MissionTest::run_set_current_cmd_while_stopped_test() cmd.content.location.lat = 12345678; cmd.content.location.lng = 23456789; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #1 : take-off to 10m @@ -914,7 +914,7 @@ void MissionTest::run_set_current_cmd_while_stopped_test() cmd.content.location.lat = 0; cmd.content.location.lng = 0; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #2 : do command @@ -925,7 +925,7 @@ void MissionTest::run_set_current_cmd_while_stopped_test() cmd.content.location.lat = 12345678; cmd.content.location.lng = 23456789; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #3 : first waypoint @@ -936,7 +936,7 @@ void MissionTest::run_set_current_cmd_while_stopped_test() cmd.content.location.lat = 12345678; cmd.content.location.lng = 23456789; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #4 : second waypoint @@ -946,7 +946,7 @@ void MissionTest::run_set_current_cmd_while_stopped_test() cmd.content.location.lng = -1234567890; cmd.content.location.alt = 22; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #5 : do command @@ -957,7 +957,7 @@ void MissionTest::run_set_current_cmd_while_stopped_test() cmd.content.location.lat = 12345678; cmd.content.location.lng = 23456789; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #6 : RTL @@ -967,7 +967,7 @@ void MissionTest::run_set_current_cmd_while_stopped_test() cmd.content.location.lng = 0; cmd.content.location.alt = 0; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // print current mission @@ -1040,7 +1040,7 @@ void MissionTest::run_replace_cmd_test() cmd.content.location.lat = 12345678; cmd.content.location.lng = 23456789; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #1 : take-off to 10m @@ -1051,7 +1051,7 @@ void MissionTest::run_replace_cmd_test() cmd.content.location.lat = 0; cmd.content.location.lng = 0; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #2 : do command @@ -1062,7 +1062,7 @@ void MissionTest::run_replace_cmd_test() cmd.content.location.lat = 12345678; cmd.content.location.lng = 23456789; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #3 : first waypoint @@ -1073,7 +1073,7 @@ void MissionTest::run_replace_cmd_test() cmd.content.location.lat = 12345678; cmd.content.location.lng = 23456789; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #4 : second waypoint @@ -1083,7 +1083,7 @@ void MissionTest::run_replace_cmd_test() cmd.content.location.lng = -1234567890; cmd.content.location.alt = 22; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // Command #6 : RTL @@ -1093,7 +1093,7 @@ void MissionTest::run_replace_cmd_test() cmd.content.location.lng = 0; cmd.content.location.alt = 0; if (!mission.add_cmd(cmd)) { - hal.console->print_P("failed to add command\n"); + hal.console->print("failed to add command\n"); } // print current mission diff --git a/libraries/AP_Notify/examples/ToshibaLED_test/ToshibaLED_test.cpp b/libraries/AP_Notify/examples/ToshibaLED_test/ToshibaLED_test.cpp index a312783a1d..ad37f3ef2c 100644 --- a/libraries/AP_Notify/examples/ToshibaLED_test/ToshibaLED_test.cpp +++ b/libraries/AP_Notify/examples/ToshibaLED_test/ToshibaLED_test.cpp @@ -15,14 +15,14 @@ static ToshibaLED_I2C toshiba_led; void setup(void) { // display welcome message - hal.console->print_P("Toshiba LED test ver 0.1\n"); + hal.console->print("Toshiba LED test ver 0.1\n"); // initialise LED toshiba_led.init(); // check if healthy if (!toshiba_led.healthy()) { - hal.console->print_P("Failed to initialise Toshiba LED\n"); + hal.console->print("Failed to initialise Toshiba LED\n"); } // turn on initialising notification @@ -36,11 +36,11 @@ void setup(void) void loop(void) { // blink test - //hal.console->print_P("Blink test\n"); + //hal.console->print("Blink test\n"); //blink(); /* // full spectrum test - hal.console->print_P("Spectrum test\n"); + hal.console->print("Spectrum test\n"); full_spectrum(); */ diff --git a/libraries/AP_PerfMon/AP_PerfMon_test/AP_PerfMon_test.cpp b/libraries/AP_PerfMon/AP_PerfMon_test/AP_PerfMon_test.cpp index b091291409..289e2b6c61 100644 --- a/libraries/AP_PerfMon/AP_PerfMon_test/AP_PerfMon_test.cpp +++ b/libraries/AP_PerfMon/AP_PerfMon_test/AP_PerfMon_test.cpp @@ -22,7 +22,7 @@ void setup() { AP_PERFMON_FUNCTION(setup) - hal.console->print_P("Performance Monitor test v1.1\n"); + hal.console->print("Performance Monitor test v1.1\n"); } void loop()