From 1b07dabeb7d8a7b5bbdb99295f1388d2994ce205 Mon Sep 17 00:00:00 2001 From: Lucas De Marchi Date: Mon, 26 Oct 2015 09:25:44 -0200 Subject: [PATCH] Replace prog_char and prog_char_t with char prog_char and prog_char_t are now the same as char on supported platforms. So, just change all places that use them and prefer char instead. AVR-specific places were not changed. --- APMrover2/GCS_Mavlink.cpp | 4 ++-- APMrover2/Rover.h | 4 ++-- APMrover2/system.cpp | 2 +- AntennaTracker/GCS_Mavlink.cpp | 4 ++-- AntennaTracker/Tracker.h | 4 ++-- ArduCopter/Copter.h | 4 ++-- ArduCopter/GCS_Mavlink.cpp | 4 ++-- ArduCopter/system.cpp | 2 +- ArduPlane/GCS_Mavlink.cpp | 4 ++-- ArduPlane/Plane.h | 4 ++-- ArduPlane/system.cpp | 2 +- libraries/APM_Control/AP_AutoTune.cpp | 6 +++--- libraries/APM_Control/AP_AutoTune.h | 6 +++--- libraries/AP_Declination/AP_Declination.cpp | 2 +- libraries/AP_GPS/AP_GPS.cpp | 6 +++--- libraries/AP_GPS/AP_GPS.h | 8 ++++---- libraries/AP_GPS/AP_GPS_MTK.cpp | 2 +- libraries/AP_GPS/AP_GPS_MTK.h | 2 +- libraries/AP_GPS/AP_GPS_NMEA.cpp | 2 +- libraries/AP_GPS/AP_GPS_NMEA.h | 14 +++++++------- libraries/AP_GPS/AP_GPS_SIRF.cpp | 2 +- libraries/AP_HAL/Scheduler.h | 2 +- libraries/AP_HAL/UARTDriver.cpp | 10 +++++----- libraries/AP_HAL/UARTDriver.h | 8 ++++---- libraries/AP_HAL/utility/BetterStream.h | 15 ++++++--------- libraries/AP_HAL/utility/ftoa_engine.cpp | 2 +- libraries/AP_HAL/utility/print_vprintf.cpp | 4 ++-- libraries/AP_HAL_Empty/Scheduler.cpp | 2 +- libraries/AP_HAL_Empty/Scheduler.h | 2 +- libraries/AP_HAL_FLYMAPLE/Scheduler.cpp | 2 +- libraries/AP_HAL_FLYMAPLE/Scheduler.h | 2 +- libraries/AP_HAL_Linux/Scheduler.cpp | 2 +- libraries/AP_HAL_Linux/Scheduler.h | 2 +- libraries/AP_HAL_PX4/Scheduler.cpp | 2 +- libraries/AP_HAL_PX4/Scheduler.h | 2 +- libraries/AP_HAL_SITL/Scheduler.cpp | 2 +- libraries/AP_HAL_SITL/Scheduler.h | 2 +- libraries/AP_HAL_VRBRAIN/Scheduler.cpp | 2 +- libraries/AP_HAL_VRBRAIN/Scheduler.h | 2 +- libraries/AP_InertialSensor/AP_InertialSensor.cpp | 2 +- libraries/AP_Limits/AP_Limit_Module.cpp | 2 +- libraries/AP_Limits/AP_Limit_Module.h | 2 +- libraries/AP_Menu/AP_Menu.cpp | 2 +- libraries/AP_Menu/AP_Menu.h | 2 +- libraries/AP_Param/AP_Param.cpp | 2 +- libraries/DataFlash/DFMessageWriter.cpp | 2 +- libraries/DataFlash/DFMessageWriter.h | 6 +++--- libraries/DataFlash/DataFlash.h | 4 ++-- libraries/DataFlash/LogFile.cpp | 5 ++--- libraries/GCS_MAVLink/GCS.h | 2 +- libraries/GCS_MAVLink/GCS_Common.cpp | 2 +- 51 files changed, 91 insertions(+), 95 deletions(-) diff --git a/APMrover2/GCS_Mavlink.cpp b/APMrover2/GCS_Mavlink.cpp index 95e93b377e..eaec9cc815 100644 --- a/APMrover2/GCS_Mavlink.cpp +++ b/APMrover2/GCS_Mavlink.cpp @@ -1426,7 +1426,7 @@ void Rover::gcs_update(void) } } -void Rover::gcs_send_text(MAV_SEVERITY severity, const prog_char_t *str) +void Rover::gcs_send_text(MAV_SEVERITY severity, const char *str) { for (uint8_t i=0; iprintln(msg); if (gcs[1].initialised && (gcs[1].get_uart() != NULL)) { gcs[1].get_uart()->println(msg); diff --git a/AntennaTracker/GCS_Mavlink.cpp b/AntennaTracker/GCS_Mavlink.cpp index 2acd819cac..fd01d907e8 100644 --- a/AntennaTracker/GCS_Mavlink.cpp +++ b/AntennaTracker/GCS_Mavlink.cpp @@ -960,7 +960,7 @@ void Tracker::gcs_update(void) } } -void Tracker::gcs_send_text(MAV_SEVERITY severity, const prog_char_t *str) +void Tracker::gcs_send_text(MAV_SEVERITY severity, const char *str) { for (uint8_t i=0; iprintln(msg); if (gcs[1].initialised && (gcs[1].get_uart() != NULL)) { gcs[1].get_uart()->println(msg); diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 1c6df7a55d..0f0aeada7c 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -1992,7 +1992,7 @@ void Plane::gcs_update(void) } } -void Plane::gcs_send_text(MAV_SEVERITY severity, const prog_char_t *str) +void Plane::gcs_send_text(MAV_SEVERITY severity, const char *str) { for (uint8_t i=0; iprintln(msg); if (gcs[1].initialised && (gcs[1].get_uart() != NULL)) { gcs[1].get_uart()->println(msg); diff --git a/libraries/APM_Control/AP_AutoTune.cpp b/libraries/APM_Control/AP_AutoTune.cpp index b1790cfabe..460c009d56 100644 --- a/libraries/APM_Control/AP_AutoTune.cpp +++ b/libraries/APM_Control/AP_AutoTune.cpp @@ -267,7 +267,7 @@ void AP_AutoTune::check_save(void) /* log a parameter change from autotune */ -void AP_AutoTune::log_param_change(float v, const prog_char_t *suffix) +void AP_AutoTune::log_param_change(float v, const char *suffix) { if (!dataflash.logging_started()) { return; @@ -288,7 +288,7 @@ void AP_AutoTune::log_param_change(float v, const prog_char_t *suffix) set a float and save a float if it has changed by more than 0.1%. This reduces the number of insignificant EEPROM writes */ -void AP_AutoTune::save_float_if_changed(AP_Float &v, float value, const prog_char_t *suffix) +void AP_AutoTune::save_float_if_changed(AP_Float &v, float value, const char *suffix) { float old_value = v.get(); v.set(value); @@ -301,7 +301,7 @@ void AP_AutoTune::save_float_if_changed(AP_Float &v, float value, const prog_cha /* set a int16 and save if changed */ -void AP_AutoTune::save_int16_if_changed(AP_Int16 &v, int16_t value, const prog_char_t *suffix) +void AP_AutoTune::save_int16_if_changed(AP_Int16 &v, int16_t value, const char *suffix) { int16_t old_value = v.get(); v.set(value); diff --git a/libraries/APM_Control/AP_AutoTune.h b/libraries/APM_Control/AP_AutoTune.h index 37b2a075d6..3fedc41c66 100644 --- a/libraries/APM_Control/AP_AutoTune.h +++ b/libraries/APM_Control/AP_AutoTune.h @@ -96,9 +96,9 @@ private: void write_log_headers(void); void write_log(float servo, float demanded, float achieved); - void log_param_change(float v, const prog_char_t *suffix); - void save_float_if_changed(AP_Float &v, float value, const prog_char_t *suffix); - void save_int16_if_changed(AP_Int16 &v, int16_t value, const prog_char_t *suffix); + void log_param_change(float v, const char *suffix); + void save_float_if_changed(AP_Float &v, float value, const char *suffix); + void save_int16_if_changed(AP_Int16 &v, int16_t value, const char *suffix); }; #endif // __AP_AUTOTUNE_H__ diff --git a/libraries/AP_Declination/AP_Declination.cpp b/libraries/AP_Declination/AP_Declination.cpp index 993f9f29fa..f744304018 100644 --- a/libraries/AP_Declination/AP_Declination.cpp +++ b/libraries/AP_Declination/AP_Declination.cpp @@ -204,7 +204,7 @@ AP_Declination::get_lookup_value(uint8_t x, uint8_t y) for(i = start_index; i < (start_index + PGM_UINT8(&declination_keys[1][x])) && current_virtual_index <= y; i++) { // Pull out the row_value struct - memcpy((void*) &stval, (const prog_char *)&declination_values[i], sizeof(struct row_value)); + memcpy((void*) &stval, (const char *)&declination_values[i], sizeof(struct row_value)); // Pull the first offset and determine sign offset = stval.abs_offset; diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index c34ebc3762..4bf45ddb1e 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -145,14 +145,14 @@ const uint32_t AP_GPS::_baudrates[] = {4800U, 38400U, 115200U, 57600U, 9600U, 23 // initialisation blobs to send to the GPS to try to get it into the // right mode -const prog_char AP_GPS::_initialisation_blob[] = UBLOX_SET_BINARY MTK_SET_BINARY SIRF_SET_BINARY; -const prog_char AP_GPS::_initialisation_raw_blob[] = UBLOX_SET_BINARY_RAW_BAUD MTK_SET_BINARY SIRF_SET_BINARY; +const char AP_GPS::_initialisation_blob[] = UBLOX_SET_BINARY MTK_SET_BINARY SIRF_SET_BINARY; +const char AP_GPS::_initialisation_raw_blob[] = UBLOX_SET_BINARY_RAW_BAUD MTK_SET_BINARY SIRF_SET_BINARY; /* send some more initialisation string bytes if there is room in the UART transmit buffer */ -void AP_GPS::send_blob_start(uint8_t instance, const prog_char *_blob, uint16_t size) +void AP_GPS::send_blob_start(uint8_t instance, const char *_blob, uint16_t size) { initblob_state[instance].blob = _blob; initblob_state[instance].remaining = size; diff --git a/libraries/AP_GPS/AP_GPS.h b/libraries/AP_GPS/AP_GPS.h index df8b07b0cc..0a052b6bbd 100644 --- a/libraries/AP_GPS/AP_GPS.h +++ b/libraries/AP_GPS/AP_GPS.h @@ -352,7 +352,7 @@ public: AP_Int8 _gnss_mode; // handle sending of initialisation strings to the GPS - void send_blob_start(uint8_t instance, const prog_char *_blob, uint16_t size); + void send_blob_start(uint8_t instance, const char *_blob, uint16_t size); void send_blob_update(uint8_t instance); // lock out a GPS port, allowing another application to use the port @@ -413,13 +413,13 @@ private: } detect_state[GPS_MAX_INSTANCES]; struct { - const prog_char *blob; + const char *blob; uint16_t remaining; } initblob_state[GPS_MAX_INSTANCES]; static const uint32_t _baudrates[]; - static const prog_char _initialisation_blob[]; - static const prog_char _initialisation_raw_blob[]; + static const char _initialisation_blob[]; + static const char _initialisation_raw_blob[]; void detect_instance(uint8_t instance); void update_instance(uint8_t instance); diff --git a/libraries/AP_GPS/AP_GPS_MTK.cpp b/libraries/AP_GPS/AP_GPS_MTK.cpp index 015d85fa59..61ecd978ca 100644 --- a/libraries/AP_GPS/AP_GPS_MTK.cpp +++ b/libraries/AP_GPS/AP_GPS_MTK.cpp @@ -26,7 +26,7 @@ // initialisation blobs to send to the GPS to try to get it into the // right mode -const prog_char AP_GPS_MTK::_initialisation_blob[] = MTK_OUTPUT_5HZ SBAS_ON WAAS_ON MTK_NAVTHRES_OFF; +const char AP_GPS_MTK::_initialisation_blob[] = MTK_OUTPUT_5HZ SBAS_ON WAAS_ON MTK_NAVTHRES_OFF; AP_GPS_MTK::AP_GPS_MTK(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port) : AP_GPS_Backend(_gps, _state, _port), diff --git a/libraries/AP_GPS/AP_GPS_MTK.h b/libraries/AP_GPS/AP_GPS_MTK.h index 822f4df92a..255ab58bae 100644 --- a/libraries/AP_GPS/AP_GPS_MTK.h +++ b/libraries/AP_GPS/AP_GPS_MTK.h @@ -78,7 +78,7 @@ private: // Buffer parse & GPS state update void _parse_gps(); - static const prog_char _initialisation_blob[]; + static const char _initialisation_blob[]; }; #endif // __AP_GPS_MTK_H__ diff --git a/libraries/AP_GPS/AP_GPS_NMEA.cpp b/libraries/AP_GPS/AP_GPS_NMEA.cpp index e1d88be9f7..885748b2bd 100644 --- a/libraries/AP_GPS/AP_GPS_NMEA.cpp +++ b/libraries/AP_GPS/AP_GPS_NMEA.cpp @@ -90,7 +90,7 @@ extern const AP_HAL::HAL& hal; "$PUBX,40,vtg,0,1,0,0,0,0*7F\r\n" /* VTG on at one per fix */ \ "$PUBX,40,rmc,0,0,0,0,0,0*67\r\n" /* RMC off (XXX suppress other message types?) */ -const prog_char AP_GPS_NMEA::_initialisation_blob[] = SIRF_INIT_MSG MTK_INIT_MSG UBLOX_INIT_MSG; +const char AP_GPS_NMEA::_initialisation_blob[] = SIRF_INIT_MSG MTK_INIT_MSG UBLOX_INIT_MSG; // NMEA message identifiers //////////////////////////////////////////////////// // diff --git a/libraries/AP_GPS/AP_GPS_NMEA.h b/libraries/AP_GPS/AP_GPS_NMEA.h index 4143b3a627..7471a12286 100644 --- a/libraries/AP_GPS/AP_GPS_NMEA.h +++ b/libraries/AP_GPS/AP_GPS_NMEA.h @@ -148,19 +148,19 @@ private: /// unit to send just the messages that we are interested /// in using these strings //@{ - static const prog_char _SiRF_init_string[]; ///< init string for SiRF units - static const prog_char _MTK_init_string[]; ///< init string for MediaTek units - static const prog_char _ublox_init_string[]; ///< init string for ublox units + static const char _SiRF_init_string[]; ///< init string for SiRF units + static const char _MTK_init_string[]; ///< init string for MediaTek units + static const char _ublox_init_string[]; ///< init string for ublox units //@} /// @name GPS message identifier strings //@{ - static const prog_char _gprmc_string[]; - static const prog_char _gpgga_string[]; - static const prog_char _gpvtg_string[]; + static const char _gprmc_string[]; + static const char _gpgga_string[]; + static const char _gpvtg_string[]; //@} - static const prog_char _initialisation_blob[]; + static const char _initialisation_blob[]; }; #endif // __AP_GPS_NMEA_H__ diff --git a/libraries/AP_GPS/AP_GPS_SIRF.cpp b/libraries/AP_GPS/AP_GPS_SIRF.cpp index e74332aedf..8e27f34568 100644 --- a/libraries/AP_GPS/AP_GPS_SIRF.cpp +++ b/libraries/AP_GPS/AP_GPS_SIRF.cpp @@ -41,7 +41,7 @@ AP_GPS_SIRF::AP_GPS_SIRF(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDr _payload_counter(0), _msg_id(0) { - gps.send_blob_start(state.instance, (const prog_char *)_initialisation_blob, sizeof(_initialisation_blob)); + gps.send_blob_start(state.instance, (const char *)_initialisation_blob, sizeof(_initialisation_blob)); } diff --git a/libraries/AP_HAL/Scheduler.h b/libraries/AP_HAL/Scheduler.h index a589450d7c..c9e2cece0e 100644 --- a/libraries/AP_HAL/Scheduler.h +++ b/libraries/AP_HAL/Scheduler.h @@ -57,7 +57,7 @@ public: virtual bool system_initializing() = 0; virtual void system_initialized() = 0; - virtual void panic(const prog_char_t *errormsg, ...) FORMAT(2, 3) NORETURN = 0; + virtual void panic(const char *errormsg, ...) FORMAT(2, 3) NORETURN = 0; virtual void reboot(bool hold_in_bootloader) = 0; /** diff --git a/libraries/AP_HAL/UARTDriver.cpp b/libraries/AP_HAL/UARTDriver.cpp index 95a4c53366..86d81adf7a 100644 --- a/libraries/AP_HAL/UARTDriver.cpp +++ b/libraries/AP_HAL/UARTDriver.cpp @@ -25,14 +25,14 @@ all boards, although they can be overridden by a port */ -void AP_HAL::UARTDriver::print_P(const prog_char_t *s) +void AP_HAL::UARTDriver::print_P(const char *s) { char c; - while ('\0' != (c = pgm_read_byte((const prog_char *)s++))) + while ('\0' != (c = pgm_read_byte((const char *)s++))) write(c); } -void AP_HAL::UARTDriver::println_P(const prog_char_t *s) +void AP_HAL::UARTDriver::println_P(const char *s) { print_P(s); println(); @@ -51,7 +51,7 @@ void AP_HAL::UARTDriver::vprintf(const char *fmt, va_list ap) print_vprintf((AP_HAL::Print*)this, 0, fmt, ap); } -void AP_HAL::UARTDriver::_printf_P(const prog_char *fmt, ...) +void AP_HAL::UARTDriver::_printf_P(const char *fmt, ...) { va_list ap; va_start(ap, fmt); @@ -59,7 +59,7 @@ void AP_HAL::UARTDriver::_printf_P(const prog_char *fmt, ...) va_end(ap); } -void AP_HAL::UARTDriver::vprintf_P(const prog_char *fmt, va_list ap) +void AP_HAL::UARTDriver::vprintf_P(const char *fmt, va_list ap) { print_vprintf((AP_HAL::Print*)this, 1, fmt, ap); } diff --git a/libraries/AP_HAL/UARTDriver.h b/libraries/AP_HAL/UARTDriver.h index 3211944b3b..597b140eac 100644 --- a/libraries/AP_HAL/UARTDriver.h +++ b/libraries/AP_HAL/UARTDriver.h @@ -51,13 +51,13 @@ public: * provided by AP_HAL to ensure consistency between ports to * different boards */ - void print_P(const prog_char_t *s); - void println_P(const prog_char_t *s); + void print_P(const char *s); + void println_P(const char *s); void printf(const char *s, ...) FORMAT(2, 3); - void _printf_P(const prog_char *s, ...) FORMAT(2, 3); + void _printf_P(const char *s, ...) FORMAT(2, 3); void vprintf(const char *s, va_list ap); - void vprintf_P(const prog_char *s, va_list ap); + void vprintf_P(const char *s, va_list ap); }; #endif // __AP_HAL_UART_DRIVER_H__ diff --git a/libraries/AP_HAL/utility/BetterStream.h b/libraries/AP_HAL/utility/BetterStream.h index 00981f3fcc..15fb20b9d0 100644 --- a/libraries/AP_HAL/utility/BetterStream.h +++ b/libraries/AP_HAL/utility/BetterStream.h @@ -25,7 +25,7 @@ #include #include -/* prog_char_t: */ +/* char: */ #include #include "Stream.h" @@ -36,25 +36,22 @@ * on _vprintf(). * Please provide your own platform-specic implementation of vprintf, sprintf, * etc. to implement the printf functions. - * - * TODO: Segregate prog_char_t dependent functions to be available on AVR - * platform only, with default implementations elsewhere. */ class AP_HAL::BetterStream : public AP_HAL::Stream { public: BetterStream(void) {} - virtual void print_P(const prog_char_t *) = 0; - virtual void println_P(const prog_char_t *) = 0; + virtual void print_P(const char *) = 0; + virtual void println_P(const char *) = 0; virtual void printf(const char *, ...) FORMAT(2, 3) = 0; /* No format checking on printf_P: can't currently support that on AVR */ - virtual void _printf_P(const prog_char *, ...) = 0; + virtual void _printf_P(const char *, ...) = 0; -#define printf_P(fmt, ...) _printf_P((const prog_char *)fmt, ## __VA_ARGS__) +#define printf_P(fmt, ...) _printf_P((const char *)fmt, ## __VA_ARGS__) virtual void vprintf(const char *, va_list) = 0; - virtual void vprintf_P(const prog_char *, va_list) = 0; + virtual void vprintf_P(const char *, va_list) = 0; }; #endif // __AP_HAL_UTILITY_BETTERSTREAM_H__ diff --git a/libraries/AP_HAL/utility/ftoa_engine.cpp b/libraries/AP_HAL/utility/ftoa_engine.cpp index 7ad12ee94d..afd4171aa9 100644 --- a/libraries/AP_HAL/utility/ftoa_engine.cpp +++ b/libraries/AP_HAL/utility/ftoa_engine.cpp @@ -33,7 +33,7 @@ #include "ftoa_engine.h" #include -#define PGM_INT8(addr) (int8_t)pgm_read_byte((const prog_char *)addr) +#define PGM_INT8(addr) (int8_t)pgm_read_byte((const char *)addr) #define PGM_UINT32(addr) pgm_read_dword((const uint32_t *)addr) /* diff --git a/libraries/AP_HAL/utility/print_vprintf.cpp b/libraries/AP_HAL/utility/print_vprintf.cpp index 55de67967b..322e9aff8d 100644 --- a/libraries/AP_HAL/utility/print_vprintf.cpp +++ b/libraries/AP_HAL/utility/print_vprintf.cpp @@ -223,10 +223,10 @@ void print_vprintf (AP_HAL::Print *s, unsigned char in_progmem, const char *fmt, } if (sign) s->write(sign); - const prog_char_t *p = "inf"; + const char *p = "inf"; if (vtype & FTOA_NAN) p = "nan"; - while ( (ndigs = pgm_read_byte((const prog_char *)p)) != 0) { + while ( (ndigs = pgm_read_byte((const char *)p)) != 0) { if (flags & FL_FLTUPP) ndigs += 'I' - 'i'; s->write(ndigs); diff --git a/libraries/AP_HAL_Empty/Scheduler.cpp b/libraries/AP_HAL_Empty/Scheduler.cpp index c2f85df8ee..52e3c8466b 100644 --- a/libraries/AP_HAL_Empty/Scheduler.cpp +++ b/libraries/AP_HAL_Empty/Scheduler.cpp @@ -71,7 +71,7 @@ bool EmptyScheduler::system_initializing() { void EmptyScheduler::system_initialized() {} -void EmptyScheduler::panic(const prog_char_t *errormsg, ...) +void EmptyScheduler::panic(const char *errormsg, ...) { va_list ap; diff --git a/libraries/AP_HAL_Empty/Scheduler.h b/libraries/AP_HAL_Empty/Scheduler.h index 9f4c7f9ffd..80b3744a93 100644 --- a/libraries/AP_HAL_Empty/Scheduler.h +++ b/libraries/AP_HAL_Empty/Scheduler.h @@ -32,7 +32,7 @@ public: bool system_initializing(); void system_initialized(); - void panic(const prog_char_t *errormsg, ...) FORMAT(2, 3) NORETURN; + void panic(const char *errormsg, ...) FORMAT(2, 3) NORETURN; void reboot(bool hold_in_bootloader); }; diff --git a/libraries/AP_HAL_FLYMAPLE/Scheduler.cpp b/libraries/AP_HAL_FLYMAPLE/Scheduler.cpp index 2dccda9d1b..5d94274ece 100644 --- a/libraries/AP_HAL_FLYMAPLE/Scheduler.cpp +++ b/libraries/AP_HAL_FLYMAPLE/Scheduler.cpp @@ -230,7 +230,7 @@ void FLYMAPLEScheduler::system_initialized() _initialized = true; } -void FLYMAPLEScheduler::panic(const prog_char_t *errormsg, ...) { +void FLYMAPLEScheduler::panic(const char *errormsg, ...) { /* Suspend timer processes. We still want the timer event to go off * to run the _failsafe code, however. */ // REVISIT: not tested on FLYMAPLE diff --git a/libraries/AP_HAL_FLYMAPLE/Scheduler.h b/libraries/AP_HAL_FLYMAPLE/Scheduler.h index 40af318e3d..2681e61d44 100644 --- a/libraries/AP_HAL_FLYMAPLE/Scheduler.h +++ b/libraries/AP_HAL_FLYMAPLE/Scheduler.h @@ -53,7 +53,7 @@ public: bool system_initializing(); void system_initialized(); - void panic(const prog_char_t *errormsg, ...) FORMAT(2, 3) NORETURN; + void panic(const char *errormsg, ...) FORMAT(2, 3) NORETURN; void reboot(bool hold_in_bootloader); private: diff --git a/libraries/AP_HAL_Linux/Scheduler.cpp b/libraries/AP_HAL_Linux/Scheduler.cpp index d8556e7119..f582deb476 100644 --- a/libraries/AP_HAL_Linux/Scheduler.cpp +++ b/libraries/AP_HAL_Linux/Scheduler.cpp @@ -407,7 +407,7 @@ void *Scheduler::_io_thread(void* arg) return NULL; } -void Scheduler::panic(const prog_char_t *errormsg, ...) +void Scheduler::panic(const char *errormsg, ...) { va_list ap; diff --git a/libraries/AP_HAL_Linux/Scheduler.h b/libraries/AP_HAL_Linux/Scheduler.h index 29291820db..5c3dffd530 100644 --- a/libraries/AP_HAL_Linux/Scheduler.h +++ b/libraries/AP_HAL_Linux/Scheduler.h @@ -43,7 +43,7 @@ public: bool system_initializing(); void system_initialized(); - void panic(const prog_char_t *errormsg, ...) FORMAT(2, 3) NORETURN; + void panic(const char *errormsg, ...) FORMAT(2, 3) NORETURN; void reboot(bool hold_in_bootloader); void stop_clock(uint64_t time_usec); diff --git a/libraries/AP_HAL_PX4/Scheduler.cpp b/libraries/AP_HAL_PX4/Scheduler.cpp index 3b92b31f7b..d479f5814c 100644 --- a/libraries/AP_HAL_PX4/Scheduler.cpp +++ b/libraries/AP_HAL_PX4/Scheduler.cpp @@ -374,7 +374,7 @@ void *PX4Scheduler::_storage_thread(void) return NULL; } -void PX4Scheduler::panic(const prog_char_t *errormsg, ...) +void PX4Scheduler::panic(const char *errormsg, ...) { va_list ap; diff --git a/libraries/AP_HAL_PX4/Scheduler.h b/libraries/AP_HAL_PX4/Scheduler.h index f03124a40d..366c313eb9 100644 --- a/libraries/AP_HAL_PX4/Scheduler.h +++ b/libraries/AP_HAL_PX4/Scheduler.h @@ -60,7 +60,7 @@ public: void suspend_timer_procs(); void resume_timer_procs(); void reboot(bool hold_in_bootloader); - void panic(const prog_char_t *errormsg, ...) FORMAT(2, 3) NORETURN; + void panic(const char *errormsg, ...) FORMAT(2, 3) NORETURN; bool in_timerprocess(); bool system_initializing(); diff --git a/libraries/AP_HAL_SITL/Scheduler.cpp b/libraries/AP_HAL_SITL/Scheduler.cpp index 66c562f3d7..20bfd4db56 100644 --- a/libraries/AP_HAL_SITL/Scheduler.cpp +++ b/libraries/AP_HAL_SITL/Scheduler.cpp @@ -259,7 +259,7 @@ void SITLScheduler::_run_io_procs(bool called_from_isr) _in_io_proc = false; } -void SITLScheduler::panic(const prog_char_t *errormsg, ...) +void SITLScheduler::panic(const char *errormsg, ...) { va_list ap; diff --git a/libraries/AP_HAL_SITL/Scheduler.h b/libraries/AP_HAL_SITL/Scheduler.h index df5827b8c8..d33239c956 100644 --- a/libraries/AP_HAL_SITL/Scheduler.h +++ b/libraries/AP_HAL_SITL/Scheduler.h @@ -41,7 +41,7 @@ public: void system_initialized(); void reboot(bool hold_in_bootloader); - void panic(const prog_char_t *errormsg, ...) FORMAT(2, 3) NORETURN; + void panic(const char *errormsg, ...) FORMAT(2, 3) NORETURN; bool interrupts_are_blocked(void) { return _nested_atomic_ctr != 0; diff --git a/libraries/AP_HAL_VRBRAIN/Scheduler.cpp b/libraries/AP_HAL_VRBRAIN/Scheduler.cpp index b5cf5d2f2c..747a8b0f96 100644 --- a/libraries/AP_HAL_VRBRAIN/Scheduler.cpp +++ b/libraries/AP_HAL_VRBRAIN/Scheduler.cpp @@ -325,7 +325,7 @@ void *VRBRAINScheduler::_io_thread(void) return NULL; } -void VRBRAINScheduler::panic(const prog_char_t *errormsg, ...) +void VRBRAINScheduler::panic(const char *errormsg, ...) { va_list ap; diff --git a/libraries/AP_HAL_VRBRAIN/Scheduler.h b/libraries/AP_HAL_VRBRAIN/Scheduler.h index cdb6691690..d56948cab6 100644 --- a/libraries/AP_HAL_VRBRAIN/Scheduler.h +++ b/libraries/AP_HAL_VRBRAIN/Scheduler.h @@ -39,7 +39,7 @@ public: void suspend_timer_procs(); void resume_timer_procs(); void reboot(bool hold_in_bootloader); - void panic(const prog_char_t *errormsg, ...) FORMAT(2, 3) NORETURN; + void panic(const char *errormsg, ...) FORMAT(2, 3) NORETURN; bool in_timerprocess(); bool system_initializing(); diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.cpp b/libraries/AP_InertialSensor/AP_InertialSensor.cpp index fc92ca1af1..f1a5cf1914 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor.cpp @@ -593,7 +593,7 @@ bool AP_InertialSensor::calibrate_accel(AP_InertialSensor_UserInteract* interact // capture data from 6 positions for (uint8_t i=0; i<6; i++) { - const prog_char_t *msg; + const char *msg; // display message to user switch ( i ) { diff --git a/libraries/AP_Limits/AP_Limit_Module.cpp b/libraries/AP_Limits/AP_Limit_Module.cpp index da3c702f5e..b9a28d0b9f 100644 --- a/libraries/AP_Limits/AP_Limit_Module.cpp +++ b/libraries/AP_Limits/AP_Limit_Module.cpp @@ -10,7 +10,7 @@ #include "AP_Limit_Module.h" -extern const prog_char_t *get_module_name(enum moduleid i) { +extern const char *get_module_name(enum moduleid i) { switch (i) { case AP_LIMITS_GPSLOCK: diff --git a/libraries/AP_Limits/AP_Limit_Module.h b/libraries/AP_Limits/AP_Limit_Module.h index 31e3f0291b..1ef11933eb 100644 --- a/libraries/AP_Limits/AP_Limit_Module.h +++ b/libraries/AP_Limits/AP_Limit_Module.h @@ -25,7 +25,7 @@ enum moduleid { AP_LIMITS_ALTITUDE = (1 << 2) }; -extern const prog_char_t *get_module_name(enum moduleid i); +extern const char *get_module_name(enum moduleid i); // an integer type big enough to fit a bit field for all modules. // We have 3 modules, so 8-bit int is enough. diff --git a/libraries/AP_Menu/AP_Menu.cpp b/libraries/AP_Menu/AP_Menu.cpp index 687c199d20..b129434da5 100644 --- a/libraries/AP_Menu/AP_Menu.cpp +++ b/libraries/AP_Menu/AP_Menu.cpp @@ -23,7 +23,7 @@ AP_HAL::BetterStream *Menu::_port; // constructor -Menu::Menu(const prog_char *prompt, const Menu::command *commands, uint8_t entries, preprompt ppfunc) : +Menu::Menu(const char *prompt, const Menu::command *commands, uint8_t entries, preprompt ppfunc) : _prompt(prompt), _commands(commands), _entries(entries), diff --git a/libraries/AP_Menu/AP_Menu.h b/libraries/AP_Menu/AP_Menu.h index 9ef66f678f..ad919634a4 100644 --- a/libraries/AP_Menu/AP_Menu.h +++ b/libraries/AP_Menu/AP_Menu.h @@ -126,7 +126,7 @@ private: /// int8_t _call(uint8_t n, uint8_t argc); - const prog_char * _prompt; ///< prompt to display + const char * _prompt; ///< prompt to display const command * _commands; ///< array of commands const uint8_t _entries; ///< size of the menu const preprompt _ppfunc; ///< optional pre-prompt action diff --git a/libraries/AP_Param/AP_Param.cpp b/libraries/AP_Param/AP_Param.cpp index 4df21ec69e..316a88e188 100644 --- a/libraries/AP_Param/AP_Param.cpp +++ b/libraries/AP_Param/AP_Param.cpp @@ -43,7 +43,7 @@ extern const AP_HAL::HAL &hal; #endif // some useful progmem macros -#define PGM_UINT8(addr) pgm_read_byte((const prog_char *)addr) +#define PGM_UINT8(addr) pgm_read_byte((const char *)addr) #define PGM_UINT16(addr) pgm_read_word((const uint16_t *)addr) #define PGM_FLOAT(addr) pgm_read_float((const float *)addr) #define PGM_POINTER(addr) pgm_read_pointer((const void *)addr) diff --git a/libraries/DataFlash/DFMessageWriter.cpp b/libraries/DataFlash/DFMessageWriter.cpp index 3b37ae0a9f..dec37581a8 100644 --- a/libraries/DataFlash/DFMessageWriter.cpp +++ b/libraries/DataFlash/DFMessageWriter.cpp @@ -144,7 +144,7 @@ void DFMessageWriter_WriteSysInfo::process() { _finished = true; // all done! } -// void DataFlash_Class::Log_Write_SysInfo(const prog_char_t *firmware_string) +// void DataFlash_Class::Log_Write_SysInfo(const char *firmware_string) // { // DFMessageWriter_WriteSysInfo writer(firmware_string); // writer->process(); diff --git a/libraries/DataFlash/DFMessageWriter.h b/libraries/DataFlash/DFMessageWriter.h index 3b1b0f685b..26562955bd 100644 --- a/libraries/DataFlash/DFMessageWriter.h +++ b/libraries/DataFlash/DFMessageWriter.h @@ -24,7 +24,7 @@ protected: class DFMessageWriter_WriteSysInfo : public DFMessageWriter { public: DFMessageWriter_WriteSysInfo(DataFlash_Class &DataFlash, - const prog_char_t *firmware_string) : + const char *firmware_string) : DFMessageWriter(DataFlash), _firmware_string(firmware_string) { } @@ -41,7 +41,7 @@ private: }; write_sysinfo_blockwriter_stage stage; - const prog_char_t *_firmware_string; + const char *_firmware_string; }; class DFMessageWriter_WriteEntireMission : public DFMessageWriter { @@ -70,7 +70,7 @@ private: class DFMessageWriter_DFLogStart : public DFMessageWriter { public: DFMessageWriter_DFLogStart(DataFlash_Class &DataFlash, - const prog_char_t *firmware_string) : + const char *firmware_string) : DFMessageWriter{DataFlash}, _writesysinfo(DataFlash, firmware_string), _writeentiremission(DataFlash) diff --git a/libraries/DataFlash/DataFlash.h b/libraries/DataFlash/DataFlash.h index 09dcf12334..25a6de6c5f 100644 --- a/libraries/DataFlash/DataFlash.h +++ b/libraries/DataFlash/DataFlash.h @@ -38,7 +38,7 @@ class DataFlash_Class public: FUNCTOR_TYPEDEF(print_mode_fn, void, AP_HAL::BetterStream*, uint8_t); FUNCTOR_TYPEDEF(vehicle_startup_message_Log_Writer, void); - DataFlash_Class(const prog_char_t *firmware_string) : + DataFlash_Class(const char *firmware_string) : _startup_messagewriter(DFMessageWriter_DFLogStart(*this,firmware_string)), _vehicle_messages(NULL) { } @@ -85,7 +85,7 @@ public: uint16_t StartNewLog(void); void AddLogFormats(const struct LogStructure *structures, uint8_t num_types); void EnableWrites(bool enable); - void Log_Write_SysInfo(const prog_char_t *firmware_string); + void Log_Write_SysInfo(const char *firmware_string); bool Log_Write_Format(const struct LogStructure *structure); bool Log_Write_Parameter(const char *name, float value); void Log_Write_GPS(const AP_GPS &gps, uint8_t instance, int32_t relative_alt); diff --git a/libraries/DataFlash/LogFile.cpp b/libraries/DataFlash/LogFile.cpp index 883ff0ddfb..4577440670 100644 --- a/libraries/DataFlash/LogFile.cpp +++ b/libraries/DataFlash/LogFile.cpp @@ -293,7 +293,7 @@ uint16_t DataFlash_Block::find_last_page_of_log(uint16_t log_number) return -1; } -#define PGM_UINT8(addr) pgm_read_byte((const prog_char *)addr) +#define PGM_UINT8(addr) pgm_read_byte((const char *)addr) #ifndef DATAFLASH_NO_CLI /* @@ -1014,7 +1014,7 @@ void DataFlash_Class::Log_Write_Vibration(const AP_InertialSensor &ins) WriteBlock(&pkt, sizeof(pkt)); } -void DataFlash_Class::Log_Write_SysInfo(const prog_char_t *firmware_string) +void DataFlash_Class::Log_Write_SysInfo(const char *firmware_string) { Log_Write_Message(firmware_string); @@ -1060,7 +1060,6 @@ bool DataFlash_Class::Log_Write_Message(const char *message) return WriteCriticalBlock(&pkt, sizeof(pkt)); } -// Write a POWR packet void DataFlash_Class::Log_Write_Power(void) { #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index 9feddda663..1ca2881f73 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -164,7 +164,7 @@ public: connections. This function is static so it can be called from any library */ - static void send_statustext_all(MAV_SEVERITY severity, const prog_char_t *fmt, ...); + static void send_statustext_all(MAV_SEVERITY severity, const char *fmt, ...); /* send a MAVLink message to all components with this vehicle's system id diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 41836e9b45..fe39364ac5 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -1172,7 +1172,7 @@ void GCS_MAVLINK::send_ahrs(AP_AHRS &ahrs) /* send a statustext message to all active MAVLink connections */ -void GCS_MAVLINK::send_statustext_all(MAV_SEVERITY severity, const prog_char_t *fmt, ...) +void GCS_MAVLINK::send_statustext_all(MAV_SEVERITY severity, const char *fmt, ...) { for (uint8_t i=0; i