From 831d8acca50ec2104e0b87e5757213844032c56e Mon Sep 17 00:00:00 2001 From: Lucas De Marchi Date: Sun, 25 Oct 2015 15:03:46 -0200 Subject: [PATCH] Remove use of PROGMEM Now variables don't have to be declared with PROGMEM anymore, so remove them. This was automated with: git grep -l -z PROGMEM | xargs -0 sed -i 's/ PROGMEM / /g' git grep -l -z PROGMEM | xargs -0 sed -i 's/PROGMEM//g' The 2 commands were done so we don't leave behind spurious spaces. AVR-specific places were not changed. --- APMrover2/APMrover2.cpp | 2 +- APMrover2/GCS_Mavlink.cpp | 2 +- APMrover2/Log.cpp | 4 ++-- APMrover2/Parameters.cpp | 4 ++-- APMrover2/setup.cpp | 2 +- APMrover2/system.cpp | 2 +- APMrover2/test.cpp | 2 +- AntennaTracker/AntennaTracker.cpp | 2 +- AntennaTracker/GCS_Mavlink.cpp | 2 +- AntennaTracker/Parameters.cpp | 2 +- ArduCopter/ArduCopter.cpp | 2 +- ArduCopter/GCS_Mavlink.cpp | 2 +- ArduCopter/Log.cpp | 4 ++-- ArduCopter/Parameters.cpp | 4 ++-- ArduCopter/setup.cpp | 2 +- ArduCopter/system.cpp | 2 +- ArduCopter/test.cpp | 2 +- ArduPlane/ArduPlane.cpp | 2 +- ArduPlane/GCS_Mavlink.cpp | 2 +- ArduPlane/Log.cpp | 4 ++-- ArduPlane/Parameters.cpp | 4 ++-- ArduPlane/arming_checks.cpp | 2 +- ArduPlane/setup.cpp | 2 +- ArduPlane/system.cpp | 2 +- ArduPlane/test.cpp | 2 +- Tools/Replay/Replay.cpp | 4 ++-- libraries/AC_AttitudeControl/AC_AttitudeControl.cpp | 2 +- libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp | 2 +- libraries/AC_AttitudeControl/AC_PosControl.cpp | 2 +- libraries/AC_Fence/AC_Fence.cpp | 2 +- libraries/AC_PID/AC_HELI_PID.cpp | 2 +- libraries/AC_PID/AC_P.cpp | 2 +- libraries/AC_PID/AC_PID.cpp | 2 +- libraries/AC_PID/AC_PI_2D.cpp | 2 +- libraries/AC_PrecLand/AC_PrecLand.cpp | 2 +- libraries/AC_Sprayer/AC_Sprayer.cpp | 2 +- libraries/AC_WPNav/AC_Circle.cpp | 2 +- libraries/AC_WPNav/AC_WPNav.cpp | 2 +- libraries/APM_Control/AP_AutoTune.cpp | 2 +- libraries/APM_Control/AP_PitchController.cpp | 2 +- libraries/APM_Control/AP_RollController.cpp | 2 +- libraries/APM_Control/AP_SteerController.cpp | 2 +- libraries/APM_Control/AP_YawController.cpp | 2 +- libraries/APM_OBC/APM_OBC.cpp | 2 +- libraries/APM_PI/APM_PI.cpp | 2 +- libraries/AP_AHRS/AP_AHRS.cpp | 2 +- libraries/AP_Airspeed/AP_Airspeed.cpp | 2 +- libraries/AP_Arming/AP_Arming.cpp | 2 +- libraries/AP_Baro/AP_Baro.cpp | 2 +- libraries/AP_BattMonitor/AP_BattMonitor.cpp | 2 +- libraries/AP_BoardConfig/AP_BoardConfig.cpp | 2 +- libraries/AP_Camera/AP_Camera.cpp | 2 +- libraries/AP_Compass/Compass.cpp | 2 +- libraries/AP_Declination/AP_Declination.cpp | 8 ++++---- libraries/AP_EPM/AP_EPM.cpp | 2 +- libraries/AP_GPS/AP_GPS.cpp | 8 ++++---- libraries/AP_GPS/AP_GPS_MTK.cpp | 2 +- libraries/AP_GPS/AP_GPS_NMEA.cpp | 8 ++++---- libraries/AP_GPS/AP_GPS_SBP.cpp | 2 +- libraries/AP_GPS/AP_GPS_SIRF.cpp | 2 +- libraries/AP_HAL/utility/ftoa_engine.cpp | 4 ++-- libraries/AP_HAL_Linux/examples/GPIOTest/GPIOTest.cpp | 2 +- libraries/AP_InertialSensor/AP_InertialSensor.cpp | 2 +- libraries/AP_InertialSensor/examples/VibTest/VibTest.cpp | 2 +- libraries/AP_L1_Control/AP_L1_Control.cpp | 2 +- libraries/AP_LandingGear/AP_LandingGear.cpp | 2 +- libraries/AP_Limits/AP_Limit_Altitude.cpp | 2 +- libraries/AP_Limits/AP_Limit_GPSLock.cpp | 2 +- libraries/AP_Limits/AP_Limit_Geofence.cpp | 2 +- libraries/AP_Limits/AP_Limits.cpp | 2 +- libraries/AP_Math/edc.cpp | 2 +- libraries/AP_Menu/AP_Menu.h | 6 +++--- libraries/AP_Mission/AP_Mission.cpp | 2 +- libraries/AP_Motors/AP_MotorsCoax.cpp | 2 +- libraries/AP_Motors/AP_MotorsHeli.cpp | 2 +- libraries/AP_Motors/AP_MotorsHeli_Single.cpp | 2 +- libraries/AP_Motors/AP_MotorsMulticopter.cpp | 2 +- libraries/AP_Motors/AP_MotorsSingle.cpp | 2 +- libraries/AP_Motors/AP_MotorsTri.cpp | 2 +- libraries/AP_Mount/AP_Mount.cpp | 2 +- libraries/AP_NavEKF/AP_NavEKF.cpp | 2 +- libraries/AP_NavEKF/AP_SmallEKF.cpp | 2 +- libraries/AP_NavEKF2/AP_NavEKF2.cpp | 2 +- libraries/AP_OpticalFlow/OpticalFlow.cpp | 2 +- libraries/AP_Parachute/AP_Parachute.cpp | 2 +- libraries/AP_RCMapper/AP_RCMapper.cpp | 2 +- libraries/AP_RPM/AP_RPM.cpp | 2 +- libraries/AP_RSSI/AP_RSSI.cpp | 2 +- libraries/AP_Rally/AP_Rally.cpp | 2 +- libraries/AP_RangeFinder/RangeFinder.cpp | 2 +- libraries/AP_Relay/AP_Relay.cpp | 2 +- libraries/AP_Scheduler/AP_Scheduler.cpp | 2 +- .../examples/Scheduler_test/Scheduler_test.cpp | 2 +- libraries/AP_SerialManager/AP_SerialManager.cpp | 2 +- libraries/AP_TECS/AP_TECS.cpp | 2 +- libraries/AP_Terrain/AP_Terrain.cpp | 2 +- .../DataFlash/examples/DataFlash_test/DataFlash_test.cpp | 2 +- libraries/GCS_MAVLink/GCS_MAVLink.cpp | 2 +- libraries/GCS_MAVLink/examples/routing/routing.cpp | 2 +- libraries/PID/PID.cpp | 2 +- libraries/RC_Channel/RC_Channel.cpp | 2 +- libraries/RC_Channel/RC_Channel_aux.cpp | 2 +- libraries/SITL/SITL.cpp | 2 +- libraries/StorageManager/StorageManager.cpp | 4 ++-- 104 files changed, 124 insertions(+), 124 deletions(-) diff --git a/APMrover2/APMrover2.cpp b/APMrover2/APMrover2.cpp index cac607d046..ea5fa76d75 100644 --- a/APMrover2/APMrover2.cpp +++ b/APMrover2/APMrover2.cpp @@ -49,7 +49,7 @@ Rover rover; with how often they should be called (in 20ms units) and the maximum time they are expected to take (in microseconds) */ -const AP_Scheduler::Task Rover::scheduler_tasks[] PROGMEM = { +const AP_Scheduler::Task Rover::scheduler_tasks[] = { SCHED_TASK(read_radio, 1, 1000), SCHED_TASK(ahrs_update, 1, 6400), SCHED_TASK(read_sonars, 1, 2000), diff --git a/APMrover2/GCS_Mavlink.cpp b/APMrover2/GCS_Mavlink.cpp index f198aae7e9..8252588fac 100644 --- a/APMrover2/GCS_Mavlink.cpp +++ b/APMrover2/GCS_Mavlink.cpp @@ -615,7 +615,7 @@ bool GCS_MAVLINK::try_send_message(enum ap_message id) /* default stream rates to 1Hz */ -const AP_Param::GroupInfo GCS_MAVLINK::var_info[] PROGMEM = { +const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = { // @Param: RAW_SENS // @DisplayName: Raw sensor stream rate // @Description: Raw sensor stream rate to ground station diff --git a/APMrover2/Log.cpp b/APMrover2/Log.cpp index 91036401c4..28c8f575e6 100644 --- a/APMrover2/Log.cpp +++ b/APMrover2/Log.cpp @@ -12,7 +12,7 @@ // and stores them in Flash memory, not RAM. // User enters the string in the console to call the functions on the right. // See class Menu in AP_Coommon for implementation details -static const struct Menu::command log_menu_commands[] PROGMEM = { +static const struct Menu::command log_menu_commands[] = { {"dump", MENU_FUNC(dump_log)}, {"erase", MENU_FUNC(erase_logs)}, {"enable", MENU_FUNC(select_logs)}, @@ -371,7 +371,7 @@ void Rover::Log_Write_Home_And_Origin() } } -const LogStructure Rover::log_structure[] PROGMEM = { +const LogStructure Rover::log_structure[] = { LOG_COMMON_STRUCTURES, { LOG_PERFORMANCE_MSG, sizeof(log_Performance), "PM", "QIHIhhhBH", "TimeUS,LTime,MLC,gDt,GDx,GDy,GDz,I2CErr,INSErr" }, diff --git a/APMrover2/Parameters.cpp b/APMrover2/Parameters.cpp index 72c7e37a8a..18987b261a 100644 --- a/APMrover2/Parameters.cpp +++ b/APMrover2/Parameters.cpp @@ -11,7 +11,7 @@ #define GOBJECT(v, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, &rover.v, {group_info:class::var_info} } #define GOBJECTN(v, pname, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## pname, &rover.v, {group_info : class::var_info} } -const AP_Param::Info Rover::var_info[] PROGMEM = { +const AP_Param::Info Rover::var_info[] = { GSCALAR(format_version, "FORMAT_VERSION", 1), GSCALAR(software_type, "SYSID_SW_TYPE", Parameters::k_software_type), @@ -551,7 +551,7 @@ const AP_Param::Info Rover::var_info[] PROGMEM = { The second column below is the index in the var_info[] table for the old object. This should be zero for top level parameters. */ -const AP_Param::ConversionInfo conversion_table[] PROGMEM = { +const AP_Param::ConversionInfo conversion_table[] = { { Parameters::k_param_battery_monitoring, 0, AP_PARAM_INT8, "BATT_MONITOR" }, { Parameters::k_param_battery_volt_pin, 0, AP_PARAM_INT8, "BATT_VOLT_PIN" }, { Parameters::k_param_battery_curr_pin, 0, AP_PARAM_INT8, "BATT_CURR_PIN" }, diff --git a/APMrover2/setup.cpp b/APMrover2/setup.cpp index 2a01fc6dcc..78d6038f4f 100644 --- a/APMrover2/setup.cpp +++ b/APMrover2/setup.cpp @@ -5,7 +5,7 @@ #if CLI_ENABLED == ENABLED // Command/function table for the setup menu -static const struct Menu::command setup_menu_commands[] PROGMEM = { +static const struct Menu::command setup_menu_commands[] = { // command function called // ======= =============== {"erase", MENU_FUNC(setup_erase)} diff --git a/APMrover2/system.cpp b/APMrover2/system.cpp index e804a2fc5a..c767e94dfa 100644 --- a/APMrover2/system.cpp +++ b/APMrover2/system.cpp @@ -25,7 +25,7 @@ int8_t Rover::main_menu_help(uint8_t argc, const Menu::arg *argv) // Command/function table for the top-level menu. -static const struct Menu::command main_menu_commands[] PROGMEM = { +static const struct Menu::command main_menu_commands[] = { // command function called // ======= =============== {"logs", MENU_FUNC(process_logs)}, diff --git a/APMrover2/test.cpp b/APMrover2/test.cpp index f4fc696a9b..8d511e9a55 100644 --- a/APMrover2/test.cpp +++ b/APMrover2/test.cpp @@ -8,7 +8,7 @@ // and stores them in Flash memory, not RAM. // User enters the string in the console to call the functions on the right. // See class Menu in AP_Common for implementation details -static const struct Menu::command test_menu_commands[] PROGMEM = { +static const struct Menu::command test_menu_commands[] = { {"pwm", MENU_FUNC(test_radio_pwm)}, {"radio", MENU_FUNC(test_radio)}, {"passthru", MENU_FUNC(test_passthru)}, diff --git a/AntennaTracker/AntennaTracker.cpp b/AntennaTracker/AntennaTracker.cpp index 4fb3c2d711..a0926baadb 100644 --- a/AntennaTracker/AntennaTracker.cpp +++ b/AntennaTracker/AntennaTracker.cpp @@ -34,7 +34,7 @@ (in 20ms units) and the maximum time they are expected to take (in microseconds) */ -const AP_Scheduler::Task Tracker::scheduler_tasks[] PROGMEM = { +const AP_Scheduler::Task Tracker::scheduler_tasks[] = { SCHED_TASK(update_ahrs, 1, 1000), SCHED_TASK(read_radio, 1, 200), SCHED_TASK(update_tracking, 1, 1000), diff --git a/AntennaTracker/GCS_Mavlink.cpp b/AntennaTracker/GCS_Mavlink.cpp index 65a5c2eea5..c08b853164 100644 --- a/AntennaTracker/GCS_Mavlink.cpp +++ b/AntennaTracker/GCS_Mavlink.cpp @@ -301,7 +301,7 @@ bool GCS_MAVLINK::try_send_message(enum ap_message id) /* default stream rates to 1Hz */ -const AP_Param::GroupInfo GCS_MAVLINK::var_info[] PROGMEM = { +const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = { // @Param: RAW_SENS // @DisplayName: Raw sensor stream rate // @Description: Raw sensor stream rate to ground station diff --git a/AntennaTracker/Parameters.cpp b/AntennaTracker/Parameters.cpp index 676d899cf6..4ea4197858 100644 --- a/AntennaTracker/Parameters.cpp +++ b/AntennaTracker/Parameters.cpp @@ -13,7 +13,7 @@ #define GOBJECT(v, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, (const void *)&tracker.v, {group_info : class::var_info} } #define GOBJECTN(v, pname, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## pname, (const void *)&tracker.v, {group_info : class::var_info} } -const AP_Param::Info Tracker::var_info[] PROGMEM = { +const AP_Param::Info Tracker::var_info[] = { GSCALAR(format_version, "FORMAT_VERSION", 0), GSCALAR(software_type, "SYSID_SW_TYPE", Parameters::k_software_type), diff --git a/ArduCopter/ArduCopter.cpp b/ArduCopter/ArduCopter.cpp index e245b5c67c..42526a8b7c 100644 --- a/ArduCopter/ArduCopter.cpp +++ b/ArduCopter/ArduCopter.cpp @@ -98,7 +98,7 @@ 4000 = 0.1hz */ -const AP_Scheduler::Task Copter::scheduler_tasks[] PROGMEM = { +const AP_Scheduler::Task Copter::scheduler_tasks[] = { SCHED_TASK(rc_loop, 4, 130), SCHED_TASK(throttle_loop, 8, 75), SCHED_TASK(update_GPS, 8, 200), diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index b4f8dd05b6..dbfb663808 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -753,7 +753,7 @@ bool GCS_MAVLINK::try_send_message(enum ap_message id) } -const AP_Param::GroupInfo GCS_MAVLINK::var_info[] PROGMEM = { +const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = { // @Param: RAW_SENS // @DisplayName: Raw sensor stream rate // @Description: Stream rate of RAW_IMU, SCALED_IMU2, SCALED_PRESSURE, and SENSOR_OFFSETS to ground station diff --git a/ArduCopter/Log.cpp b/ArduCopter/Log.cpp index 33120d8649..ee20c9610b 100644 --- a/ArduCopter/Log.cpp +++ b/ArduCopter/Log.cpp @@ -13,7 +13,7 @@ // and stores them in Flash memory, not RAM. // User enters the string in the console to call the functions on the right. // See class Menu in AP_Coommon for implementation details -static const struct Menu::command log_menu_commands[] PROGMEM = { +static const struct Menu::command log_menu_commands[] = { {"dump", MENU_FUNC(dump_log)}, {"erase", MENU_FUNC(erase_logs)}, {"enable", MENU_FUNC(select_logs)}, @@ -719,7 +719,7 @@ void Copter::Log_Write_Precland() #endif // PRECISION_LANDING == ENABLED } -const struct LogStructure Copter::log_structure[] PROGMEM = { +const struct LogStructure Copter::log_structure[] = { LOG_COMMON_STRUCTURES, #if AUTOTUNE_ENABLED == ENABLED { LOG_AUTOTUNE_MSG, sizeof(log_AutoTune), diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 29363c8c82..d7288331c7 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -28,7 +28,7 @@ #define GOBJECT(v, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, (const void *)&copter.v, {group_info : class::var_info} } #define GOBJECTN(v, pname, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## pname, (const void *)&copter.v, {group_info : class::var_info} } -const AP_Param::Info Copter::var_info[] PROGMEM = { +const AP_Param::Info Copter::var_info[] = { // @Param: SYSID_SW_MREV // @DisplayName: Eeprom format version number // @Description: This value is incremented when changes are made to the eeprom format @@ -1132,7 +1132,7 @@ const AP_Param::Info Copter::var_info[] PROGMEM = { The second column below is the index in the var_info[] table for the old object. This should be zero for top level parameters. */ -const AP_Param::ConversionInfo conversion_table[] PROGMEM = { +const AP_Param::ConversionInfo conversion_table[] = { { Parameters::k_param_battery_monitoring, 0, AP_PARAM_INT8, "BATT_MONITOR" }, { Parameters::k_param_battery_volt_pin, 0, AP_PARAM_INT8, "BATT_VOLT_PIN" }, { Parameters::k_param_battery_curr_pin, 0, AP_PARAM_INT8, "BATT_CURR_PIN" }, diff --git a/ArduCopter/setup.cpp b/ArduCopter/setup.cpp index a69fa4dbac..553b517a5d 100644 --- a/ArduCopter/setup.cpp +++ b/ArduCopter/setup.cpp @@ -9,7 +9,7 @@ #endif // Command/function table for the setup menu -static const struct Menu::command setup_menu_commands[] PROGMEM = { +static const struct Menu::command setup_menu_commands[] = { {"reset", MENU_FUNC(setup_factory)}, {"show", MENU_FUNC(setup_show)}, {"set", MENU_FUNC(setup_set)}, diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index b9005bbf97..bc90a0e667 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -24,7 +24,7 @@ int8_t Copter::main_menu_help(uint8_t argc, const Menu::arg *argv) } // Command/function table for the top-level menu. -const struct Menu::command main_menu_commands[] PROGMEM = { +const struct Menu::command main_menu_commands[] = { // command function called // ======= =============== {"logs", MENU_FUNC(process_logs)}, diff --git a/ArduCopter/test.cpp b/ArduCopter/test.cpp index 9283687c9a..6e68837e90 100644 --- a/ArduCopter/test.cpp +++ b/ArduCopter/test.cpp @@ -8,7 +8,7 @@ // and stores them in Flash memory, not RAM. // User enters the string in the console to call the functions on the right. // See class Menu in AP_Coommon for implementation details -static const struct Menu::command test_menu_commands[] PROGMEM = { +static const struct Menu::command test_menu_commands[] = { #if HIL_MODE == HIL_MODE_DISABLED {"baro", MENU_FUNC(test_baro)}, #endif diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index f38f785547..02df8bc36d 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -36,7 +36,7 @@ often they should be called (in 20ms units) and the maximum time they are expected to take (in microseconds) */ -const AP_Scheduler::Task Plane::scheduler_tasks[] PROGMEM = { +const AP_Scheduler::Task Plane::scheduler_tasks[] = { SCHED_TASK(read_radio, 1, 700), SCHED_TASK(check_short_failsafe, 1, 1000), SCHED_TASK(ahrs_update, 1, 6400), diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 7915da6fb3..53bbc83e32 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -844,7 +844,7 @@ bool GCS_MAVLINK::try_send_message(enum ap_message id) /* default stream rates to 1Hz */ -const AP_Param::GroupInfo GCS_MAVLINK::var_info[] PROGMEM = { +const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = { // @Param: RAW_SENS // @DisplayName: Raw sensor stream rate // @Description: Raw sensor stream rate to ground station diff --git a/ArduPlane/Log.cpp b/ArduPlane/Log.cpp index 1a086a67ec..210d5b0909 100644 --- a/ArduPlane/Log.cpp +++ b/ArduPlane/Log.cpp @@ -12,7 +12,7 @@ // and stores them in Flash memory, not RAM. // User enters the string in the console to call the functions on the right. // See class Menu in AP_Coommon for implementation details -static const struct Menu::command log_menu_commands[] PROGMEM = { +static const struct Menu::command log_menu_commands[] = { {"dump", MENU_FUNC(dump_log)}, {"erase", MENU_FUNC(erase_logs)}, {"enable", MENU_FUNC(select_logs)}, @@ -475,7 +475,7 @@ void Plane::Log_Write_Home_And_Origin() } } -static const struct LogStructure log_structure[] PROGMEM = { +static const struct LogStructure log_structure[] = { LOG_COMMON_STRUCTURES, { LOG_PERFORMANCE_MSG, sizeof(log_Performance), "PM", "QIHIhhhBH", "TimeUS,LTime,MLC,gDt,GDx,GDy,GDz,I2CErr,INSErr" }, diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index b21a20b969..50708aab31 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -13,7 +13,7 @@ #define GOBJECT(v, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, (const void *)&plane.v, {group_info : class::var_info} } #define GOBJECTN(v, pname, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## pname, (const void *)&plane.v, {group_info : class::var_info} } -const AP_Param::Info Plane::var_info[] PROGMEM = { +const AP_Param::Info Plane::var_info[] = { // @Param: FORMAT_VERSION // @DisplayName: Eeprom format version number // @Description: This value is incremented when changes are made to the eeprom format @@ -1230,7 +1230,7 @@ const AP_Param::Info Plane::var_info[] PROGMEM = { The second column below is the index in the var_info[] table for the old object. This should be zero for top level parameters. */ -const AP_Param::ConversionInfo conversion_table[] PROGMEM = { +const AP_Param::ConversionInfo conversion_table[] = { { Parameters::k_param_pidServoRoll, 0, AP_PARAM_FLOAT, "RLL2SRV_P" }, { Parameters::k_param_pidServoRoll, 1, AP_PARAM_FLOAT, "RLL2SRV_I" }, { Parameters::k_param_pidServoRoll, 2, AP_PARAM_FLOAT, "RLL2SRV_D" }, diff --git a/ArduPlane/arming_checks.cpp b/ArduPlane/arming_checks.cpp index 8236e6b63d..b7c663e5ec 100644 --- a/ArduPlane/arming_checks.cpp +++ b/ArduPlane/arming_checks.cpp @@ -4,7 +4,7 @@ */ #include "Plane.h" -const AP_Param::GroupInfo AP_Arming_Plane::var_info[] PROGMEM = { +const AP_Param::GroupInfo AP_Arming_Plane::var_info[] = { // variables from parent vehicle AP_NESTEDGROUPINFO(AP_Arming, 0), diff --git a/ArduPlane/setup.cpp b/ArduPlane/setup.cpp index baf5a45a9b..cdf496fce8 100644 --- a/ArduPlane/setup.cpp +++ b/ArduPlane/setup.cpp @@ -5,7 +5,7 @@ #if CLI_ENABLED == ENABLED // Command/function table for the setup menu -static const struct Menu::command setup_menu_commands[] PROGMEM = { +static const struct Menu::command setup_menu_commands[] = { // command function called // ======= =============== {"reset", MENU_FUNC(setup_factory)}, diff --git a/ArduPlane/system.cpp b/ArduPlane/system.cpp index 1c66546d74..587efc0283 100644 --- a/ArduPlane/system.cpp +++ b/ArduPlane/system.cpp @@ -24,7 +24,7 @@ int8_t Plane::main_menu_help(uint8_t argc, const Menu::arg *argv) } // Command/function table for the top-level menu. -static const struct Menu::command main_menu_commands[] PROGMEM = { +static const struct Menu::command main_menu_commands[] = { // command function called // ======= =============== {"logs", MENU_FUNC(process_logs)}, diff --git a/ArduPlane/test.cpp b/ArduPlane/test.cpp index 79cab0cffa..a69f14e03f 100644 --- a/ArduPlane/test.cpp +++ b/ArduPlane/test.cpp @@ -8,7 +8,7 @@ // and stores them in Flash memory, not RAM. // User enters the string in the console to call the functions on the right. // See class Menu in AP_Common for implementation details -static const struct Menu::command test_menu_commands[] PROGMEM = { +static const struct Menu::command test_menu_commands[] = { {"pwm", MENU_FUNC(test_radio_pwm)}, {"radio", MENU_FUNC(test_radio)}, {"passthru", MENU_FUNC(test_passthru)}, diff --git a/Tools/Replay/Replay.cpp b/Tools/Replay/Replay.cpp index 5165406192..8941c20305 100644 --- a/Tools/Replay/Replay.cpp +++ b/Tools/Replay/Replay.cpp @@ -107,7 +107,7 @@ ReplayVehicle replayvehicle; #define GOBJECT(v, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, &replayvehicle.v, {group_info : class::var_info} } #define GOBJECTN(v, pname, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## pname, &replayvehicle.v, {group_info : class::var_info} } -const AP_Param::Info ReplayVehicle::var_info[] PROGMEM = { +const AP_Param::Info ReplayVehicle::var_info[] = { GSCALAR(dummy, "_DUMMY", 0), // barometer ground calibration. The GND_ prefix is chosen for @@ -173,7 +173,7 @@ enum { LOG_CHEK_MSG=100 }; -static const struct LogStructure log_structure[] PROGMEM = { +static const struct LogStructure log_structure[] = { LOG_COMMON_STRUCTURES, { LOG_CHEK_MSG, sizeof(log_Chek), "CHEK", "QccCLLffff", "TimeUS,Roll,Pitch,Yaw,Lat,Lng,Alt,VN,VE,VD" } diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp index 2ed0c0efd1..f7e7e148af 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp @@ -5,7 +5,7 @@ #include // table of user settable parameters -const AP_Param::GroupInfo AC_AttitudeControl::var_info[] PROGMEM = { +const AP_Param::GroupInfo AC_AttitudeControl::var_info[] = { // 0, 1 were RATE_RP_MAX, RATE_Y_MAX diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp index 4b26fb4057..7676df7f1b 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp @@ -4,7 +4,7 @@ #include // table of user settable parameters -const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] PROGMEM = { +const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] = { // parameters from parent vehicle AP_NESTEDGROUPINFO(AC_AttitudeControl, 0), diff --git a/libraries/AC_AttitudeControl/AC_PosControl.cpp b/libraries/AC_AttitudeControl/AC_PosControl.cpp index c31ff9dc24..c6e5daccde 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl.cpp +++ b/libraries/AC_AttitudeControl/AC_PosControl.cpp @@ -5,7 +5,7 @@ extern const AP_HAL::HAL& hal; -const AP_Param::GroupInfo AC_PosControl::var_info[] PROGMEM = { +const AP_Param::GroupInfo AC_PosControl::var_info[] = { // 0 was used for HOVER // @Param: _ACC_XY_FILT diff --git a/libraries/AC_Fence/AC_Fence.cpp b/libraries/AC_Fence/AC_Fence.cpp index a4c166e51d..5782b06b85 100644 --- a/libraries/AC_Fence/AC_Fence.cpp +++ b/libraries/AC_Fence/AC_Fence.cpp @@ -4,7 +4,7 @@ extern const AP_HAL::HAL& hal; -const AP_Param::GroupInfo AC_Fence::var_info[] PROGMEM = { +const AP_Param::GroupInfo AC_Fence::var_info[] = { // @Param: ENABLE // @DisplayName: Fence enable/disable // @Description: Allows you to enable (1) or disable (0) the fence functionality diff --git a/libraries/AC_PID/AC_HELI_PID.cpp b/libraries/AC_PID/AC_HELI_PID.cpp index 6afaa7b65a..0ea31c1151 100644 --- a/libraries/AC_PID/AC_HELI_PID.cpp +++ b/libraries/AC_PID/AC_HELI_PID.cpp @@ -6,7 +6,7 @@ #include #include "AC_HELI_PID.h" -const AP_Param::GroupInfo AC_HELI_PID::var_info[] PROGMEM = { +const AP_Param::GroupInfo AC_HELI_PID::var_info[] = { // @Param: P // @DisplayName: PID Proportional Gain // @Description: P Gain which produces an output value that is proportional to the current error value diff --git a/libraries/AC_PID/AC_P.cpp b/libraries/AC_PID/AC_P.cpp index 40045ad7df..2b6a29d364 100644 --- a/libraries/AC_PID/AC_P.cpp +++ b/libraries/AC_PID/AC_P.cpp @@ -6,7 +6,7 @@ #include #include "AC_P.h" -const AP_Param::GroupInfo AC_P::var_info[] PROGMEM = { +const AP_Param::GroupInfo AC_P::var_info[] = { // @Param: P // @DisplayName: PI Proportional Gain // @Description: P Gain which produces an output value that is proportional to the current error value diff --git a/libraries/AC_PID/AC_PID.cpp b/libraries/AC_PID/AC_PID.cpp index 20bd131d32..6ed8988004 100644 --- a/libraries/AC_PID/AC_PID.cpp +++ b/libraries/AC_PID/AC_PID.cpp @@ -6,7 +6,7 @@ #include #include "AC_PID.h" -const AP_Param::GroupInfo AC_PID::var_info[] PROGMEM = { +const AP_Param::GroupInfo AC_PID::var_info[] = { // @Param: P // @DisplayName: PID Proportional Gain // @Description: P Gain which produces an output value that is proportional to the current error value diff --git a/libraries/AC_PID/AC_PI_2D.cpp b/libraries/AC_PID/AC_PI_2D.cpp index af161c6d7b..78f5df524b 100644 --- a/libraries/AC_PID/AC_PI_2D.cpp +++ b/libraries/AC_PID/AC_PI_2D.cpp @@ -6,7 +6,7 @@ #include #include "AC_PI_2D.h" -const AP_Param::GroupInfo AC_PI_2D::var_info[] PROGMEM = { +const AP_Param::GroupInfo AC_PI_2D::var_info[] = { // @Param: P // @DisplayName: PID Proportional Gain // @Description: P Gain which produces an output value that is proportional to the current error value diff --git a/libraries/AC_PrecLand/AC_PrecLand.cpp b/libraries/AC_PrecLand/AC_PrecLand.cpp index 668a36429a..4f270ddb00 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand.cpp @@ -7,7 +7,7 @@ extern const AP_HAL::HAL& hal; -const AP_Param::GroupInfo AC_PrecLand::var_info[] PROGMEM = { +const AP_Param::GroupInfo AC_PrecLand::var_info[] = { // @DisplayName: Precision Land enabled/disabled and behaviour // @Description: Precision Land enabled/disabled and behaviour // @Values: 0:Disabled, 1:Enabled Always Land, 2:Enabled Strict diff --git a/libraries/AC_Sprayer/AC_Sprayer.cpp b/libraries/AC_Sprayer/AC_Sprayer.cpp index 8a5cda9799..269450416f 100644 --- a/libraries/AC_Sprayer/AC_Sprayer.cpp +++ b/libraries/AC_Sprayer/AC_Sprayer.cpp @@ -7,7 +7,7 @@ extern const AP_HAL::HAL& hal; // ------------------------------ -const AP_Param::GroupInfo AC_Sprayer::var_info[] PROGMEM = { +const AP_Param::GroupInfo AC_Sprayer::var_info[] = { // @Param: ENABLE // @DisplayName: Sprayer enable/disable // @Description: Allows you to enable (1) or disable (0) the sprayer diff --git a/libraries/AC_WPNav/AC_Circle.cpp b/libraries/AC_WPNav/AC_Circle.cpp index 05ab94f802..ba5cfb870f 100644 --- a/libraries/AC_WPNav/AC_Circle.cpp +++ b/libraries/AC_WPNav/AC_Circle.cpp @@ -5,7 +5,7 @@ extern const AP_HAL::HAL& hal; -const AP_Param::GroupInfo AC_Circle::var_info[] PROGMEM = { +const AP_Param::GroupInfo AC_Circle::var_info[] = { // @Param: RADIUS // @DisplayName: Circle Radius // @Description: Defines the radius of the circle the vehicle will fly when in Circle flight mode diff --git a/libraries/AC_WPNav/AC_WPNav.cpp b/libraries/AC_WPNav/AC_WPNav.cpp index 82537642bc..7cb37936e8 100644 --- a/libraries/AC_WPNav/AC_WPNav.cpp +++ b/libraries/AC_WPNav/AC_WPNav.cpp @@ -4,7 +4,7 @@ extern const AP_HAL::HAL& hal; -const AP_Param::GroupInfo AC_WPNav::var_info[] PROGMEM = { +const AP_Param::GroupInfo AC_WPNav::var_info[] = { // index 0 was used for the old orientation matrix // @Param: SPEED diff --git a/libraries/APM_Control/AP_AutoTune.cpp b/libraries/APM_Control/AP_AutoTune.cpp index 6351cabc2f..b1790cfabe 100644 --- a/libraries/APM_Control/AP_AutoTune.cpp +++ b/libraries/APM_Control/AP_AutoTune.cpp @@ -95,7 +95,7 @@ static const struct { float tau; float Dratio; float rmax; -} tuning_table[] PROGMEM = { +} tuning_table[] = { { 0.70f, 0.050f, 20 }, // level 1 { 0.65f, 0.055f, 30 }, // level 2 { 0.60f, 0.060f, 40 }, // level 3 diff --git a/libraries/APM_Control/AP_PitchController.cpp b/libraries/APM_Control/AP_PitchController.cpp index 146db57c15..69d3f2103b 100644 --- a/libraries/APM_Control/AP_PitchController.cpp +++ b/libraries/APM_Control/AP_PitchController.cpp @@ -22,7 +22,7 @@ extern const AP_HAL::HAL& hal; -const AP_Param::GroupInfo AP_PitchController::var_info[] PROGMEM = { +const AP_Param::GroupInfo AP_PitchController::var_info[] = { // @Param: TCONST // @DisplayName: Pitch Time Constant diff --git a/libraries/APM_Control/AP_RollController.cpp b/libraries/APM_Control/AP_RollController.cpp index 3147364a22..9996f31a96 100644 --- a/libraries/APM_Control/AP_RollController.cpp +++ b/libraries/APM_Control/AP_RollController.cpp @@ -23,7 +23,7 @@ extern const AP_HAL::HAL& hal; -const AP_Param::GroupInfo AP_RollController::var_info[] PROGMEM = { +const AP_Param::GroupInfo AP_RollController::var_info[] = { // @Param: TCONST // @DisplayName: Roll Time Constant // @Description: This controls the time constant in seconds from demanded to achieved bank angle. A value of 0.5 is a good default and will work with nearly all models. Advanced users may want to reduce this time to obtain a faster response but there is no point setting a time less than the aircraft can achieve. diff --git a/libraries/APM_Control/AP_SteerController.cpp b/libraries/APM_Control/AP_SteerController.cpp index c97dd746b7..022d260754 100644 --- a/libraries/APM_Control/AP_SteerController.cpp +++ b/libraries/APM_Control/AP_SteerController.cpp @@ -24,7 +24,7 @@ extern const AP_HAL::HAL& hal; -const AP_Param::GroupInfo AP_SteerController::var_info[] PROGMEM = { +const AP_Param::GroupInfo AP_SteerController::var_info[] = { // @Param: TCONST // @DisplayName: Steering Time Constant // @Description: This controls the time constant in seconds from demanded to achieved steering angle. A value of 0.75 is a good default and will work with nearly all rovers. Ground steering in aircraft needs a bit smaller time constant, and a value of 0.5 is recommended for best ground handling in fixed wing aircraft. A value of 0.75 means that the controller will try to correct any deviation between the desired and actual steering angle in 0.75 seconds. Advanced users may want to reduce this time to obtain a faster response but there is no point setting a time less than the vehicle can achieve. diff --git a/libraries/APM_Control/AP_YawController.cpp b/libraries/APM_Control/AP_YawController.cpp index 5fde166630..3357b397ed 100644 --- a/libraries/APM_Control/AP_YawController.cpp +++ b/libraries/APM_Control/AP_YawController.cpp @@ -23,7 +23,7 @@ extern const AP_HAL::HAL& hal; -const AP_Param::GroupInfo AP_YawController::var_info[] PROGMEM = { +const AP_Param::GroupInfo AP_YawController::var_info[] = { // @Param: SLIP // @DisplayName: Sideslip control gain diff --git a/libraries/APM_OBC/APM_OBC.cpp b/libraries/APM_OBC/APM_OBC.cpp index 4d5b6b93bd..f080d2c2b3 100644 --- a/libraries/APM_OBC/APM_OBC.cpp +++ b/libraries/APM_OBC/APM_OBC.cpp @@ -29,7 +29,7 @@ extern const AP_HAL::HAL& hal; // table of user settable parameters -const AP_Param::GroupInfo APM_OBC::var_info[] PROGMEM = { +const AP_Param::GroupInfo APM_OBC::var_info[] = { // @Param: MAN_PIN // @DisplayName: Manual Pin // @Description: This sets a digital output pin to set high when in manual mode diff --git a/libraries/APM_PI/APM_PI.cpp b/libraries/APM_PI/APM_PI.cpp index 34c230ce70..b7395f1e38 100644 --- a/libraries/APM_PI/APM_PI.cpp +++ b/libraries/APM_PI/APM_PI.cpp @@ -7,7 +7,7 @@ #include "APM_PI.h" -const AP_Param::GroupInfo APM_PI::var_info[] PROGMEM = { +const AP_Param::GroupInfo APM_PI::var_info[] = { AP_GROUPINFO("P", 0, APM_PI, _kp, 0), AP_GROUPINFO("I", 1, APM_PI, _ki, 0), AP_GROUPINFO("IMAX", 2, APM_PI, _imax, 0), diff --git a/libraries/AP_AHRS/AP_AHRS.cpp b/libraries/AP_AHRS/AP_AHRS.cpp index 3441ad2b29..ab4bd230bf 100644 --- a/libraries/AP_AHRS/AP_AHRS.cpp +++ b/libraries/AP_AHRS/AP_AHRS.cpp @@ -20,7 +20,7 @@ extern const AP_HAL::HAL& hal; // table of user settable parameters -const AP_Param::GroupInfo AP_AHRS::var_info[] PROGMEM = { +const AP_Param::GroupInfo AP_AHRS::var_info[] = { // index 0 and 1 are for old parameters that are no longer not used // @Param: GPS_GAIN diff --git a/libraries/AP_Airspeed/AP_Airspeed.cpp b/libraries/AP_Airspeed/AP_Airspeed.cpp index e85aed0a98..5e9d3a9a3f 100644 --- a/libraries/AP_Airspeed/AP_Airspeed.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed.cpp @@ -67,7 +67,7 @@ extern const AP_HAL::HAL& hal; #endif // table of user settable parameters -const AP_Param::GroupInfo AP_Airspeed::var_info[] PROGMEM = { +const AP_Param::GroupInfo AP_Airspeed::var_info[] = { // @Param: ENABLE // @DisplayName: Airspeed enable diff --git a/libraries/AP_Arming/AP_Arming.cpp b/libraries/AP_Arming/AP_Arming.cpp index 3e30dbfcae..d53f48481f 100644 --- a/libraries/AP_Arming/AP_Arming.cpp +++ b/libraries/AP_Arming/AP_Arming.cpp @@ -26,7 +26,7 @@ extern const AP_HAL::HAL& hal; -const AP_Param::GroupInfo AP_Arming::var_info[] PROGMEM = { +const AP_Param::GroupInfo AP_Arming::var_info[] = { // @Param: REQUIRE // @DisplayName: Require Arming Motors // @Description: Arming disabled until some requirements are met. If 0, there are no requirements (arm immediately). If 1, require rudder stick or GCS arming before arming motors and send THR_MIN PWM to throttle channel when disarmed. If 2, require rudder stick or GCS arming and send 0 PWM to throttle channel when disarmed. See the ARMING_CHECK_* parameters to see what checks are done before arming. Note, if setting this parameter to 0 a reboot is required to arm the plane. Also note, even with this parameter at 0, if ARMING_CHECK parameter is not also zero the plane may fail to arm throttle at boot due to a pre-arm check failure. diff --git a/libraries/AP_Baro/AP_Baro.cpp b/libraries/AP_Baro/AP_Baro.cpp index eb34f612fc..ccdc8f8fb2 100644 --- a/libraries/AP_Baro/AP_Baro.cpp +++ b/libraries/AP_Baro/AP_Baro.cpp @@ -27,7 +27,7 @@ extern const AP_HAL::HAL& hal; // table of user settable parameters -const AP_Param::GroupInfo AP_Baro::var_info[] PROGMEM = { +const AP_Param::GroupInfo AP_Baro::var_info[] = { // NOTE: Index numbers 0 and 1 were for the old integer // ground temperature and pressure diff --git a/libraries/AP_BattMonitor/AP_BattMonitor.cpp b/libraries/AP_BattMonitor/AP_BattMonitor.cpp index 33b5b8b338..c6747b73c1 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor.cpp @@ -6,7 +6,7 @@ extern const AP_HAL::HAL& hal; -const AP_Param::GroupInfo AP_BattMonitor::var_info[] PROGMEM = { +const AP_Param::GroupInfo AP_BattMonitor::var_info[] = { // @Param: _MONITOR // @DisplayName: Battery monitoring // @Description: Controls enabling monitoring of the battery's voltage and current diff --git a/libraries/AP_BoardConfig/AP_BoardConfig.cpp b/libraries/AP_BoardConfig/AP_BoardConfig.cpp index e6fc49a36b..b5588b183f 100644 --- a/libraries/AP_BoardConfig/AP_BoardConfig.cpp +++ b/libraries/AP_BoardConfig/AP_BoardConfig.cpp @@ -44,7 +44,7 @@ extern const AP_HAL::HAL& hal; // table of user settable parameters -const AP_Param::GroupInfo AP_BoardConfig::var_info[] PROGMEM = { +const AP_Param::GroupInfo AP_BoardConfig::var_info[] = { #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 // @Param: PWM_COUNT // @DisplayName: PWM Count diff --git a/libraries/AP_Camera/AP_Camera.cpp b/libraries/AP_Camera/AP_Camera.cpp index 1eee9ce1c9..0f6c0cbfa5 100644 --- a/libraries/AP_Camera/AP_Camera.cpp +++ b/libraries/AP_Camera/AP_Camera.cpp @@ -9,7 +9,7 @@ // ------------------------------ #define CAM_DEBUG DISABLED -const AP_Param::GroupInfo AP_Camera::var_info[] PROGMEM = { +const AP_Param::GroupInfo AP_Camera::var_info[] = { // @Param: TRIGG_TYPE // @DisplayName: Camera shutter (trigger) type // @Description: how to trigger the camera to take a picture diff --git a/libraries/AP_Compass/Compass.cpp b/libraries/AP_Compass/Compass.cpp index 12da6eccb0..debdc4c230 100644 --- a/libraries/AP_Compass/Compass.cpp +++ b/libraries/AP_Compass/Compass.cpp @@ -12,7 +12,7 @@ extern AP_HAL::HAL& hal; #define COMPASS_LEARN_DEFAULT 1 #endif -const AP_Param::GroupInfo Compass::var_info[] PROGMEM = { +const AP_Param::GroupInfo Compass::var_info[] = { // index 0 was used for the old orientation matrix // @Param: OFS_X diff --git a/libraries/AP_Declination/AP_Declination.cpp b/libraries/AP_Declination/AP_Declination.cpp index 70dce1b306..993f9f29fa 100644 --- a/libraries/AP_Declination/AP_Declination.cpp +++ b/libraries/AP_Declination/AP_Declination.cpp @@ -45,7 +45,7 @@ struct row_value { }; // 730 bytes -static const uint8_t exceptions[10][73] PROGMEM = \ +static const uint8_t exceptions[10][73] = \ { \ {150,145,140,135,130,125,120,115,110,105,100,95,90,85,80,75,70,65,60,55,50,45,40,35,30,25,20,15,10,5,0,4,9,14,19,24,29,34,39,44,49,54,59,64,69,74,79,84,89,94,99,104,109,114,119,124,129,134,139,144,149,154,159,164,169,174,179,175,170,165,160,155,150}, \ {143,137,131,126,120,115,110,105,100,95,90,85,80,75,71,66,62,57,53,48,44,39,35,31,27,22,18,14,9,5,1,3,7,11,16,20,25,29,34,38,43,47,52,57,61,66,71,76,81,86,91,96,101,107,112,117,123,128,134,140,146,151,157,163,169,175,178,172,166,160,154,148,143}, \ @@ -60,7 +60,7 @@ static const uint8_t exceptions[10][73] PROGMEM = \ }; // 100 bytes -static const uint8_t exception_signs[10][10] PROGMEM = \ +static const uint8_t exception_signs[10][10] = \ { \ {0,0,0,1,255,255,224,0,0,0}, \ {0,0,0,1,255,255,240,0,0,0}, \ @@ -75,7 +75,7 @@ static const uint8_t exception_signs[10][10] PROGMEM = \ }; // 76 bytes -static const uint8_t declination_keys[2][37] PROGMEM = \ +static const uint8_t declination_keys[2][37] = \ { \ // Row start values {36,30,25,21,18,16,14,12,11,10,9,9,9,8,8,8,7,6,6,5,4,4,4,3,4,4,4}, \ @@ -84,7 +84,7 @@ static const uint8_t declination_keys[2][37] PROGMEM = \ }; // 1056 total values @ 1 byte each = 1056 bytes -static const row_value declination_values[] PROGMEM = \ +static const row_value declination_values[] = \ { \ {0,0,4},{1,1,0},{0,0,2},{1,1,0},{0,0,2},{1,1,3},{2,1,1},{3,1,3},{4,1,1},{3,1,1},{2,1,1},{3,1,0},{2,1,0},{1,1,0},{2,1,1},{1,1,0},{2,1,0},{3,1,4},{4,1,1},{3,1,0},{4,1,0},{3,1,2},{2,1,2},{1,1,1},{0,0,0},{1,0,1},{3,0,0},{4,0,0},{6,0,0},{8,0,0},{11,0,0},{13,0,1},{10,0,0},{9,0,0},{7,0,0},{5,0,0},{4,0,0},{2,0,0},{1,0,2}, \ {0,0,6},{1,1,0},{0,0,6},{1,1,2},{2,1,0},{3,1,2},{4,1,2},{3,1,3},{2,1,0},{1,1,0},{2,1,0},{1,1,2},{2,1,2},{3,1,3},{4,1,0},{3,1,3},{2,1,1},{1,1,1},{0,0,0},{1,0,1},{2,0,0},{4,0,0},{5,0,0},{6,0,0},{7,0,0},{8,0,0},{9,0,0},{8,0,0},{6,0,0},{7,0,0},{6,0,0},{4,0,1},{3,0,0},{2,0,0},{1,0,0},{2,0,0},{0,0,0},{1,0,0}, \ diff --git a/libraries/AP_EPM/AP_EPM.cpp b/libraries/AP_EPM/AP_EPM.cpp index 970f951e37..d1ccecfde6 100644 --- a/libraries/AP_EPM/AP_EPM.cpp +++ b/libraries/AP_EPM/AP_EPM.cpp @@ -12,7 +12,7 @@ extern const AP_HAL::HAL& hal; -const AP_Param::GroupInfo AP_EPM::var_info[] PROGMEM = { +const AP_Param::GroupInfo AP_EPM::var_info[] = { // @Param: ENABLE // @DisplayName: EPM Enable/Disable // @Description: EPM enable/disable diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index 5aeba6a9b8..7d3e1bb652 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -23,7 +23,7 @@ extern const AP_HAL::HAL& hal; // table of user settable parameters -const AP_Param::GroupInfo AP_GPS::var_info[] PROGMEM = { +const AP_Param::GroupInfo AP_GPS::var_info[] = { // @Param: TYPE // @DisplayName: GPS type // @Description: GPS type @@ -141,12 +141,12 @@ void AP_GPS::init(DataFlash_Class *dataflash, const AP_SerialManager& serial_man } // baudrates to try to detect GPSes with -const uint32_t AP_GPS::_baudrates[] PROGMEM = {4800U, 38400U, 115200U, 57600U, 9600U, 230400U}; +const uint32_t AP_GPS::_baudrates[] = {4800U, 38400U, 115200U, 57600U, 9600U, 230400U}; // initialisation blobs to send to the GPS to try to get it into the // right mode -const prog_char AP_GPS::_initialisation_blob[] PROGMEM = UBLOX_SET_BINARY MTK_SET_BINARY SIRF_SET_BINARY; -const prog_char AP_GPS::_initialisation_raw_blob[] PROGMEM = UBLOX_SET_BINARY_RAW_BAUD MTK_SET_BINARY SIRF_SET_BINARY; +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; /* send some more initialisation string bytes if there is room in the diff --git a/libraries/AP_GPS/AP_GPS_MTK.cpp b/libraries/AP_GPS/AP_GPS_MTK.cpp index 8b1d07af43..015d85fa59 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[] PROGMEM = MTK_OUTPUT_5HZ SBAS_ON WAAS_ON MTK_NAVTHRES_OFF; +const prog_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_NMEA.cpp b/libraries/AP_GPS/AP_GPS_NMEA.cpp index 55a3a2983c..e1d88be9f7 100644 --- a/libraries/AP_GPS/AP_GPS_NMEA.cpp +++ b/libraries/AP_GPS/AP_GPS_NMEA.cpp @@ -90,13 +90,13 @@ 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[] PROGMEM = SIRF_INIT_MSG MTK_INIT_MSG UBLOX_INIT_MSG; +const prog_char AP_GPS_NMEA::_initialisation_blob[] = SIRF_INIT_MSG MTK_INIT_MSG UBLOX_INIT_MSG; // NMEA message identifiers //////////////////////////////////////////////////// // -const char AP_GPS_NMEA::_gprmc_string[] PROGMEM = "GPRMC"; -const char AP_GPS_NMEA::_gpgga_string[] PROGMEM = "GPGGA"; -const char AP_GPS_NMEA::_gpvtg_string[] PROGMEM = "GPVTG"; +const char AP_GPS_NMEA::_gprmc_string[] = "GPRMC"; +const char AP_GPS_NMEA::_gpgga_string[] = "GPGGA"; +const char AP_GPS_NMEA::_gpvtg_string[] = "GPVTG"; // Convenience macros ////////////////////////////////////////////////////////// // diff --git a/libraries/AP_GPS/AP_GPS_SBP.cpp b/libraries/AP_GPS/AP_GPS_SBP.cpp index 7ac0911d3c..2e0959daf0 100644 --- a/libraries/AP_GPS/AP_GPS_SBP.cpp +++ b/libraries/AP_GPS/AP_GPS_SBP.cpp @@ -434,7 +434,7 @@ struct PACKED log_SbpRAW2 { }; -static const struct LogStructure sbp_log_structures[] PROGMEM = { +static const struct LogStructure sbp_log_structures[] = { { LOG_MSG_SBPHEALTH, sizeof(log_SbpHealth), "SBPH", "QIII", "TimeUS,CrcError,LastInject,IARhyp" }, { LOG_MSG_SBPRAW1, sizeof(log_SbpRAW1), diff --git a/libraries/AP_GPS/AP_GPS_SIRF.cpp b/libraries/AP_GPS/AP_GPS_SIRF.cpp index 385a0b210e..e74332aedf 100644 --- a/libraries/AP_GPS/AP_GPS_SIRF.cpp +++ b/libraries/AP_GPS/AP_GPS_SIRF.cpp @@ -28,7 +28,7 @@ // // XXX the bytes show up on the wire, but at least my test unit (EM-411) seems to ignore them. // -const uint8_t AP_GPS_SIRF::_initialisation_blob[] PROGMEM = { +const uint8_t AP_GPS_SIRF::_initialisation_blob[] = { 0xa0, 0xa2, 0x00, 0x08, 0xa6, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xa8, 0xb0, 0xb3, 0xa0, 0xa2, 0x00, 0x08, 0xa6, 0x00, 0x29, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0xd0, 0xb0, 0xb3 }; diff --git a/libraries/AP_HAL/utility/ftoa_engine.cpp b/libraries/AP_HAL/utility/ftoa_engine.cpp index 954ebb85b0..7ad12ee94d 100644 --- a/libraries/AP_HAL/utility/ftoa_engine.cpp +++ b/libraries/AP_HAL/utility/ftoa_engine.cpp @@ -44,14 +44,14 @@ * f = factorTable[i] * e = exponentTable[i] */ -static const int8_t exponentTable[32] PROGMEM = { +static const int8_t exponentTable[32] = { -36, -33, -31, -29, -26, -24, -21, -19, -17, -14, -12, -9, -7, -4, -2, 0, 3, 5, 8, 10, 12, 15, 17, 20, 22, 24, 27, 29, 32, 34, 36, 39 }; -static const uint32_t factorTable[32] PROGMEM = { +static const uint32_t factorTable[32] = { 2295887404UL, 587747175UL, 1504632769UL, diff --git a/libraries/AP_HAL_Linux/examples/GPIOTest/GPIOTest.cpp b/libraries/AP_HAL_Linux/examples/GPIOTest/GPIOTest.cpp index 272cd96841..bfa2af4730 100644 --- a/libraries/AP_HAL_Linux/examples/GPIOTest/GPIOTest.cpp +++ b/libraries/AP_HAL_Linux/examples/GPIOTest/GPIOTest.cpp @@ -97,7 +97,7 @@ public: MenuCommands commands; -const struct Menu::command test_menu_commands[] PROGMEM = { +const struct Menu::command test_menu_commands[] = { {"input", MENU_FUNC(gpio_input)}, {"output", MENU_FUNC(gpio_output)}, {"input_ch", MENU_FUNC(gpio_input_channel)}, diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.cpp b/libraries/AP_InertialSensor/AP_InertialSensor.cpp index cb9ccaaa99..8439c6a84b 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor.cpp @@ -43,7 +43,7 @@ extern const AP_HAL::HAL& hal; #define SAMPLE_UNIT 1 // Class level parameters -const AP_Param::GroupInfo AP_InertialSensor::var_info[] PROGMEM = { +const AP_Param::GroupInfo AP_InertialSensor::var_info[] = { // @Param: PRODUCT_ID // @DisplayName: IMU Product ID // @Description: Which type of IMU is installed (read-only). diff --git a/libraries/AP_InertialSensor/examples/VibTest/VibTest.cpp b/libraries/AP_InertialSensor/examples/VibTest/VibTest.cpp index df6a9b7067..8c8c1df62d 100644 --- a/libraries/AP_InertialSensor/examples/VibTest/VibTest.cpp +++ b/libraries/AP_InertialSensor/examples/VibTest/VibTest.cpp @@ -58,7 +58,7 @@ static uint32_t gyro_deltat_min[INS_MAX_INSTANCES]; static uint32_t gyro_deltat_max[INS_MAX_INSTANCES]; static DataFlash_File DataFlash("/fs/microsd/VIBTEST"); -static const struct LogStructure log_structure[] PROGMEM = { +static const struct LogStructure log_structure[] = { LOG_COMMON_STRUCTURES, LOG_EXTRA_STRUCTURES }; diff --git a/libraries/AP_L1_Control/AP_L1_Control.cpp b/libraries/AP_L1_Control/AP_L1_Control.cpp index c6a3eb9aa6..369e59e406 100644 --- a/libraries/AP_L1_Control/AP_L1_Control.cpp +++ b/libraries/AP_L1_Control/AP_L1_Control.cpp @@ -6,7 +6,7 @@ extern const AP_HAL::HAL& hal; // table of user settable parameters -const AP_Param::GroupInfo AP_L1_Control::var_info[] PROGMEM = { +const AP_Param::GroupInfo AP_L1_Control::var_info[] = { // @Param: PERIOD // @DisplayName: L1 control period // @Description: Period in seconds of L1 tracking loop. This parameter is the primary control for agressiveness of turns in auto mode. This needs to be larger for less responsive airframes. The default of 20 is quite conservative, but for most RC aircraft will lead to reasonable flight. For smaller more agile aircraft a value closer to 15 is appropriate, or even as low as 10 for some very agile aircraft. When tuning, change this value in small increments, as a value that is much too small (say 5 or 10 below the right value) can lead to very radical turns, and a risk of stalling. diff --git a/libraries/AP_LandingGear/AP_LandingGear.cpp b/libraries/AP_LandingGear/AP_LandingGear.cpp index 159f0bf81b..89a453279f 100644 --- a/libraries/AP_LandingGear/AP_LandingGear.cpp +++ b/libraries/AP_LandingGear/AP_LandingGear.cpp @@ -8,7 +8,7 @@ extern const AP_HAL::HAL& hal; -const AP_Param::GroupInfo AP_LandingGear::var_info[] PROGMEM = { +const AP_Param::GroupInfo AP_LandingGear::var_info[] = { // @Param: SERVO_RTRACT // @DisplayName: Landing Gear Servo Retracted PWM Value diff --git a/libraries/AP_Limits/AP_Limit_Altitude.cpp b/libraries/AP_Limits/AP_Limit_Altitude.cpp index f7ebb66555..d2ef1f13fa 100644 --- a/libraries/AP_Limits/AP_Limit_Altitude.cpp +++ b/libraries/AP_Limits/AP_Limit_Altitude.cpp @@ -10,7 +10,7 @@ #include "AP_Limit_Altitude.h" -const AP_Param::GroupInfo AP_Limit_Altitude::var_info[] PROGMEM = { +const AP_Param::GroupInfo AP_Limit_Altitude::var_info[] = { // @Param: ALT_ON // @DisplayName: Enable altitude // @Description: Setting this to Enabled(1) will enable the altitude. Setting this to Disabled(0) will disable the altitude diff --git a/libraries/AP_Limits/AP_Limit_GPSLock.cpp b/libraries/AP_Limits/AP_Limit_GPSLock.cpp index 4e5740aa0f..8f209803e6 100644 --- a/libraries/AP_Limits/AP_Limit_GPSLock.cpp +++ b/libraries/AP_Limits/AP_Limit_GPSLock.cpp @@ -10,7 +10,7 @@ #include "AP_Limit_GPSLock.h" -const AP_Param::GroupInfo AP_Limit_GPSLock::var_info[] PROGMEM = { +const AP_Param::GroupInfo AP_Limit_GPSLock::var_info[] = { // @Param: GPSLCK_ON // @DisplayName: Enable gpslock // @Description: Setting this to Enabled(1) will enable the gpslock. Setting this to Disabled(0) will disable the gpslock diff --git a/libraries/AP_Limits/AP_Limit_Geofence.cpp b/libraries/AP_Limits/AP_Limit_Geofence.cpp index ab9223debd..2849c7ba33 100644 --- a/libraries/AP_Limits/AP_Limit_Geofence.cpp +++ b/libraries/AP_Limits/AP_Limit_Geofence.cpp @@ -12,7 +12,7 @@ extern const AP_HAL::HAL& hal; -const AP_Param::GroupInfo AP_Limit_Geofence::var_info[] PROGMEM = { +const AP_Param::GroupInfo AP_Limit_Geofence::var_info[] = { // @Param: FNC_ON // @DisplayName: Enable Geofence // @Description: Setting this to Enabled(1) will enable the geofence. Setting this to Disabled(0) will disable the geofence diff --git a/libraries/AP_Limits/AP_Limits.cpp b/libraries/AP_Limits/AP_Limits.cpp index fbc8975ec9..50137c40c9 100644 --- a/libraries/AP_Limits/AP_Limits.cpp +++ b/libraries/AP_Limits/AP_Limits.cpp @@ -9,7 +9,7 @@ #include "AP_Limits.h" #include "AP_Limit_Module.h" -const AP_Param::GroupInfo AP_Limits::var_info[] PROGMEM = { +const AP_Param::GroupInfo AP_Limits::var_info[] = { // @Param: ENABLED // @DisplayName: Enable Limits Library diff --git a/libraries/AP_Math/edc.cpp b/libraries/AP_Math/edc.cpp index 7d93dddd73..a4ad5f2b42 100644 --- a/libraries/AP_Math/edc.cpp +++ b/libraries/AP_Math/edc.cpp @@ -13,7 +13,7 @@ #include "edc.h" /* CRC16 implementation acording to CCITT standards */ -static const uint16_t crc16tab[256] PROGMEM = { +static const uint16_t crc16tab[256] = { 0x0000, 0x1021, 0x2042, 0x3063, 0x4084, 0x50A5, 0x60C6, 0x70E7, 0x8108, 0x9129, 0xA14A, 0xB16B, 0xC18C, 0xD1AD, 0xE1CE, 0xF1EF, 0x1231, 0x0210, 0x3273, 0x2252, 0x52B5, 0x4294, 0x72F7, 0x62D6, diff --git a/libraries/AP_Menu/AP_Menu.h b/libraries/AP_Menu/AP_Menu.h index 4ed6377df5..9ef66f678f 100644 --- a/libraries/AP_Menu/AP_Menu.h +++ b/libraries/AP_Menu/AP_Menu.h @@ -98,7 +98,7 @@ public: /// the MENU and MENU2 macros defined below. /// /// @param prompt The prompt to be displayed with this menu. - /// @param commands An array of ::command structures in program memory (PROGMEM). + /// @param commands An array of ::command structures in program memory. /// @param entries The number of entries in the menu. /// Menu(const char *prompt, const struct command *commands, uint8_t entries, preprompt ppfunc = 0); @@ -167,11 +167,11 @@ private: /// The MENU2 macro supports the optional pre-prompt printing function. /// #define MENU(name, prompt, commands) \ - static const char __menu_name__ ## name[] PROGMEM = prompt; \ + static const char __menu_name__ ## name[] = prompt; \ static Menu name(__menu_name__ ## name, commands, ARRAY_SIZE(commands)) #define MENU2(name, prompt, commands, preprompt) \ - static const char __menu_name__ ## name[] PROGMEM = prompt; \ + static const char __menu_name__ ## name[] = prompt; \ static Menu name(__menu_name__ ## name, commands, ARRAY_SIZE(commands), preprompt) #endif // __AP_COMMON_MENU_H__ diff --git a/libraries/AP_Mission/AP_Mission.cpp b/libraries/AP_Mission/AP_Mission.cpp index 11151557cc..a24b3db736 100644 --- a/libraries/AP_Mission/AP_Mission.cpp +++ b/libraries/AP_Mission/AP_Mission.cpp @@ -6,7 +6,7 @@ #include "AP_Mission.h" #include -const AP_Param::GroupInfo AP_Mission::var_info[] PROGMEM = { +const AP_Param::GroupInfo AP_Mission::var_info[] = { // @Param: TOTAL // @DisplayName: Total mission commands diff --git a/libraries/AP_Motors/AP_MotorsCoax.cpp b/libraries/AP_Motors/AP_MotorsCoax.cpp index 117108e50e..c284edb087 100644 --- a/libraries/AP_Motors/AP_MotorsCoax.cpp +++ b/libraries/AP_Motors/AP_MotorsCoax.cpp @@ -27,7 +27,7 @@ extern const AP_HAL::HAL& hal; -const AP_Param::GroupInfo AP_MotorsCoax::var_info[] PROGMEM = { +const AP_Param::GroupInfo AP_MotorsCoax::var_info[] = { // variables from parent vehicle AP_NESTEDGROUPINFO(AP_MotorsMulticopter, 0), diff --git a/libraries/AP_Motors/AP_MotorsHeli.cpp b/libraries/AP_Motors/AP_MotorsHeli.cpp index 72d2f46629..66b1fb9336 100644 --- a/libraries/AP_Motors/AP_MotorsHeli.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli.cpp @@ -26,7 +26,7 @@ extern const AP_HAL::HAL& hal; -const AP_Param::GroupInfo AP_MotorsHeli::var_info[] PROGMEM = { +const AP_Param::GroupInfo AP_MotorsHeli::var_info[] = { // @Param: ROL_MAX // @DisplayName: Swash Roll Angle Max diff --git a/libraries/AP_Motors/AP_MotorsHeli_Single.cpp b/libraries/AP_Motors/AP_MotorsHeli_Single.cpp index eeba1fdf35..c4c82df7d1 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Single.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Single.cpp @@ -20,7 +20,7 @@ extern const AP_HAL::HAL& hal; -const AP_Param::GroupInfo AP_MotorsHeli_Single::var_info[] PROGMEM = { +const AP_Param::GroupInfo AP_MotorsHeli_Single::var_info[] = { AP_NESTEDGROUPINFO(AP_MotorsHeli, 0), // @Param: SV1_POS diff --git a/libraries/AP_Motors/AP_MotorsMulticopter.cpp b/libraries/AP_Motors/AP_MotorsMulticopter.cpp index 71d7c6f491..0fe3873970 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.cpp +++ b/libraries/AP_Motors/AP_MotorsMulticopter.cpp @@ -25,7 +25,7 @@ extern const AP_HAL::HAL& hal; // parameters for the motor class -const AP_Param::GroupInfo AP_MotorsMulticopter::var_info[] PROGMEM = { +const AP_Param::GroupInfo AP_MotorsMulticopter::var_info[] = { // 0 was used by TB_RATIO // 1,2,3 were used by throttle curve diff --git a/libraries/AP_Motors/AP_MotorsSingle.cpp b/libraries/AP_Motors/AP_MotorsSingle.cpp index 651eb9398a..461b8bfd14 100644 --- a/libraries/AP_Motors/AP_MotorsSingle.cpp +++ b/libraries/AP_Motors/AP_MotorsSingle.cpp @@ -27,7 +27,7 @@ extern const AP_HAL::HAL& hal; -const AP_Param::GroupInfo AP_MotorsSingle::var_info[] PROGMEM = { +const AP_Param::GroupInfo AP_MotorsSingle::var_info[] = { // variables from parent vehicle AP_NESTEDGROUPINFO(AP_MotorsMulticopter, 0), diff --git a/libraries/AP_Motors/AP_MotorsTri.cpp b/libraries/AP_Motors/AP_MotorsTri.cpp index a84bf487b1..e61afa597a 100644 --- a/libraries/AP_Motors/AP_MotorsTri.cpp +++ b/libraries/AP_Motors/AP_MotorsTri.cpp @@ -25,7 +25,7 @@ extern const AP_HAL::HAL& hal; -const AP_Param::GroupInfo AP_MotorsTri::var_info[] PROGMEM = { +const AP_Param::GroupInfo AP_MotorsTri::var_info[] = { // variables from parent vehicle AP_NESTEDGROUPINFO(AP_MotorsMulticopter, 0), diff --git a/libraries/AP_Mount/AP_Mount.cpp b/libraries/AP_Mount/AP_Mount.cpp index 90b8469fba..0e28cf0f80 100644 --- a/libraries/AP_Mount/AP_Mount.cpp +++ b/libraries/AP_Mount/AP_Mount.cpp @@ -11,7 +11,7 @@ #include "AP_Mount_SToRM32.h" #include "AP_Mount_SToRM32_serial.h" -const AP_Param::GroupInfo AP_Mount::var_info[] PROGMEM = { +const AP_Param::GroupInfo AP_Mount::var_info[] = { // @Param: _DEFLT_MODE // @DisplayName: Mount default operating mode // @Description: Mount default operating mode on startup and after control is returned from autopilot diff --git a/libraries/AP_NavEKF/AP_NavEKF.cpp b/libraries/AP_NavEKF/AP_NavEKF.cpp index 64d41e320d..106b42302e 100644 --- a/libraries/AP_NavEKF/AP_NavEKF.cpp +++ b/libraries/AP_NavEKF/AP_NavEKF.cpp @@ -116,7 +116,7 @@ extern const AP_HAL::HAL& hal; #define MAX_GYRO_BIAS 0.1745f // Define tuning parameters -const AP_Param::GroupInfo NavEKF::var_info[] PROGMEM = { +const AP_Param::GroupInfo NavEKF::var_info[] = { // @Param: VELNE_NOISE // @DisplayName: GPS horizontal velocity measurement noise scaler diff --git a/libraries/AP_NavEKF/AP_SmallEKF.cpp b/libraries/AP_NavEKF/AP_SmallEKF.cpp index db16e3a286..4b77c9214c 100644 --- a/libraries/AP_NavEKF/AP_SmallEKF.cpp +++ b/libraries/AP_NavEKF/AP_SmallEKF.cpp @@ -23,7 +23,7 @@ extern const AP_HAL::HAL& hal; // Define tuning parameters -const AP_Param::GroupInfo SmallEKF::var_info[] PROGMEM = { +const AP_Param::GroupInfo SmallEKF::var_info[] = { AP_GROUPEND }; diff --git a/libraries/AP_NavEKF2/AP_NavEKF2.cpp b/libraries/AP_NavEKF2/AP_NavEKF2.cpp index 1bbdec4337..8449c6839f 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2.cpp @@ -85,7 +85,7 @@ #endif // APM_BUILD_DIRECTORY // Define tuning parameters -const AP_Param::GroupInfo NavEKF2::var_info[] PROGMEM = { +const AP_Param::GroupInfo NavEKF2::var_info[] = { // @Param: ENABLE // @DisplayName: Enable EKF2 diff --git a/libraries/AP_OpticalFlow/OpticalFlow.cpp b/libraries/AP_OpticalFlow/OpticalFlow.cpp index 7fcaf5edb5..653c67399f 100644 --- a/libraries/AP_OpticalFlow/OpticalFlow.cpp +++ b/libraries/AP_OpticalFlow/OpticalFlow.cpp @@ -5,7 +5,7 @@ extern const AP_HAL::HAL& hal; -const AP_Param::GroupInfo OpticalFlow::var_info[] PROGMEM = { +const AP_Param::GroupInfo OpticalFlow::var_info[] = { // @Param: _ENABLE // @DisplayName: Optical flow enable/disable // @Description: Setting this to Enabled(1) will enable optical flow. Setting this to Disabled(0) will disable optical flow diff --git a/libraries/AP_Parachute/AP_Parachute.cpp b/libraries/AP_Parachute/AP_Parachute.cpp index ca0a3ee61b..0a0c3d8bc5 100644 --- a/libraries/AP_Parachute/AP_Parachute.cpp +++ b/libraries/AP_Parachute/AP_Parachute.cpp @@ -9,7 +9,7 @@ extern const AP_HAL::HAL& hal; -const AP_Param::GroupInfo AP_Parachute::var_info[] PROGMEM = { +const AP_Param::GroupInfo AP_Parachute::var_info[] = { // @Param: ENABLED // @DisplayName: Parachute release enabled or disabled diff --git a/libraries/AP_RCMapper/AP_RCMapper.cpp b/libraries/AP_RCMapper/AP_RCMapper.cpp index 99ad30ce66..31239e3f9c 100644 --- a/libraries/AP_RCMapper/AP_RCMapper.cpp +++ b/libraries/AP_RCMapper/AP_RCMapper.cpp @@ -3,7 +3,7 @@ #include #include "AP_RCMapper.h" -const AP_Param::GroupInfo RCMapper::var_info[] PROGMEM = { +const AP_Param::GroupInfo RCMapper::var_info[] = { // @Param: ROLL // @DisplayName: Roll channel // @Description: Roll channel number. This is useful when you have a RC transmitter that can't change the channel order easily. Roll is normally on channel 1, but you can move it to any channel with this parameter. Reboot is required for changes to take effect. diff --git a/libraries/AP_RPM/AP_RPM.cpp b/libraries/AP_RPM/AP_RPM.cpp index 2de9b63724..a5b14d8c02 100644 --- a/libraries/AP_RPM/AP_RPM.cpp +++ b/libraries/AP_RPM/AP_RPM.cpp @@ -20,7 +20,7 @@ extern const AP_HAL::HAL& hal; // table of user settable parameters -const AP_Param::GroupInfo AP_RPM::var_info[] PROGMEM = { +const AP_Param::GroupInfo AP_RPM::var_info[] = { // @Param: _TYPE // @DisplayName: RPM type // @Description: What type of RPM sensor is connected diff --git a/libraries/AP_RSSI/AP_RSSI.cpp b/libraries/AP_RSSI/AP_RSSI.cpp index 24e14f66f1..3514d01119 100644 --- a/libraries/AP_RSSI/AP_RSSI.cpp +++ b/libraries/AP_RSSI/AP_RSSI.cpp @@ -20,7 +20,7 @@ extern const AP_HAL::HAL& hal; -const AP_Param::GroupInfo AP_RSSI::var_info[] PROGMEM = { +const AP_Param::GroupInfo AP_RSSI::var_info[] = { // @Param: TYPE // @DisplayName: RSSI Type diff --git a/libraries/AP_Rally/AP_Rally.cpp b/libraries/AP_Rally/AP_Rally.cpp index 5878e30c34..d9aac93623 100644 --- a/libraries/AP_Rally/AP_Rally.cpp +++ b/libraries/AP_Rally/AP_Rally.cpp @@ -32,7 +32,7 @@ StorageAccess AP_Rally::_storage(StorageManager::StorageRally); #define RALLY_INCLUDE_HOME_DEFAULT 0 #endif -const AP_Param::GroupInfo AP_Rally::var_info[] PROGMEM = { +const AP_Param::GroupInfo AP_Rally::var_info[] = { // @Param: TOTAL // @DisplayName: Rally Total // @Description: Number of rally points currently loaded diff --git a/libraries/AP_RangeFinder/RangeFinder.cpp b/libraries/AP_RangeFinder/RangeFinder.cpp index 5b595b3c11..c49bfcb812 100644 --- a/libraries/AP_RangeFinder/RangeFinder.cpp +++ b/libraries/AP_RangeFinder/RangeFinder.cpp @@ -25,7 +25,7 @@ #include "AP_RangeFinder_LightWareSerial.h" // table of user settable parameters -const AP_Param::GroupInfo RangeFinder::var_info[] PROGMEM = { +const AP_Param::GroupInfo RangeFinder::var_info[] = { // @Param: _TYPE // @DisplayName: Rangefinder type // @Description: What type of rangefinder device that is connected diff --git a/libraries/AP_Relay/AP_Relay.cpp b/libraries/AP_Relay/AP_Relay.cpp index 1ede464b9c..1b6f177a5e 100644 --- a/libraries/AP_Relay/AP_Relay.cpp +++ b/libraries/AP_Relay/AP_Relay.cpp @@ -33,7 +33,7 @@ #define RELAY2_PIN_DEFAULT -1 #endif -const AP_Param::GroupInfo AP_Relay::var_info[] PROGMEM = { +const AP_Param::GroupInfo AP_Relay::var_info[] = { // @Param: PIN // @DisplayName: First Relay Pin // @Description: Digital pin number for first relay control. This is the pin used for camera control. diff --git a/libraries/AP_Scheduler/AP_Scheduler.cpp b/libraries/AP_Scheduler/AP_Scheduler.cpp index ea42d61436..8334f34fd9 100644 --- a/libraries/AP_Scheduler/AP_Scheduler.cpp +++ b/libraries/AP_Scheduler/AP_Scheduler.cpp @@ -28,7 +28,7 @@ extern const AP_HAL::HAL& hal; int8_t AP_Scheduler::current_task = -1; -const AP_Param::GroupInfo AP_Scheduler::var_info[] PROGMEM = { +const AP_Param::GroupInfo AP_Scheduler::var_info[] = { // @Param: DEBUG // @DisplayName: Scheduler debug level // @Description: Set to non-zero to enable scheduler debug messages. When set to show "Slips" the scheduler will display a message whenever a scheduled task is delayed due to too much CPU load. When set to ShowOverruns the scheduled will display a message whenever a task takes longer than the limit promised in the task table. diff --git a/libraries/AP_Scheduler/examples/Scheduler_test/Scheduler_test.cpp b/libraries/AP_Scheduler/examples/Scheduler_test/Scheduler_test.cpp index 356374ce00..29ca1ef9f2 100644 --- a/libraries/AP_Scheduler/examples/Scheduler_test/Scheduler_test.cpp +++ b/libraries/AP_Scheduler/examples/Scheduler_test/Scheduler_test.cpp @@ -42,7 +42,7 @@ static SchedTest schedtest; often they should be called (in 20ms units) and the maximum time they are expected to take (in microseconds) */ -const AP_Scheduler::Task SchedTest::scheduler_tasks[] PROGMEM = { +const AP_Scheduler::Task SchedTest::scheduler_tasks[] = { SCHED_TASK(ins_update, 1, 1000), SCHED_TASK(one_hz_print, 50, 1000), SCHED_TASK(five_second_call, 250, 1800), diff --git a/libraries/AP_SerialManager/AP_SerialManager.cpp b/libraries/AP_SerialManager/AP_SerialManager.cpp index 20b819526e..63771441fb 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.cpp +++ b/libraries/AP_SerialManager/AP_SerialManager.cpp @@ -26,7 +26,7 @@ extern const AP_HAL::HAL& hal; -const AP_Param::GroupInfo AP_SerialManager::var_info[] PROGMEM = { +const AP_Param::GroupInfo AP_SerialManager::var_info[] = { // @Param: 0_BAUD // @DisplayName: Serial0 baud rate // @Description: The baud rate used on the USB console. The APM2 can support all baudrates up to 115, and also can support 500. The PX4 can support rates of up to 1500. If you setup a rate you cannot support on APM2 and then can't connect to your board you should load a firmware from a different vehicle type. That will reset all your parameters to defaults. diff --git a/libraries/AP_TECS/AP_TECS.cpp b/libraries/AP_TECS/AP_TECS.cpp index 0ea48b83ff..8b2a5d4f61 100644 --- a/libraries/AP_TECS/AP_TECS.cpp +++ b/libraries/AP_TECS/AP_TECS.cpp @@ -14,7 +14,7 @@ extern const AP_HAL::HAL& hal; //Debug("%.2f %.2f %.2f %.2f \n", var1, var2, var3, var4); // table of user settable parameters -const AP_Param::GroupInfo AP_TECS::var_info[] PROGMEM = { +const AP_Param::GroupInfo AP_TECS::var_info[] = { // @Param: CLMB_MAX // @DisplayName: Maximum Climb Rate (metres/sec) diff --git a/libraries/AP_Terrain/AP_Terrain.cpp b/libraries/AP_Terrain/AP_Terrain.cpp index 58e2f7e5e6..b7eb63d31f 100644 --- a/libraries/AP_Terrain/AP_Terrain.cpp +++ b/libraries/AP_Terrain/AP_Terrain.cpp @@ -35,7 +35,7 @@ extern const AP_HAL::HAL& hal; // table of user settable parameters -const AP_Param::GroupInfo AP_Terrain::var_info[] PROGMEM = { +const AP_Param::GroupInfo AP_Terrain::var_info[] = { // @Param: ENABLE // @DisplayName: Terrain data enable // @Description: enable terrain data. This enables the vehicle storing a database of terrain data on the SD card. The terrain data is requested from the ground station as needed, and stored for later use on the SD card. To be useful the ground station must support TERRAIN_REQUEST messages and have access to a terrain database, such as the SRTM database. diff --git a/libraries/DataFlash/examples/DataFlash_test/DataFlash_test.cpp b/libraries/DataFlash/examples/DataFlash_test/DataFlash_test.cpp index 848043cd5d..073789b381 100644 --- a/libraries/DataFlash/examples/DataFlash_test/DataFlash_test.cpp +++ b/libraries/DataFlash/examples/DataFlash_test/DataFlash_test.cpp @@ -17,7 +17,7 @@ struct PACKED log_Test { int32_t l1, l2; }; -static const struct LogStructure log_structure[] PROGMEM = { +static const struct LogStructure log_structure[] = { LOG_COMMON_STRUCTURES, { LOG_TEST_MSG, sizeof(log_Test), "TEST", "HHHHii", "V1,V2,V3,V4,L1,L2" } diff --git a/libraries/GCS_MAVLink/GCS_MAVLink.cpp b/libraries/GCS_MAVLink/GCS_MAVLink.cpp index e43e22f039..0503f0b509 100644 --- a/libraries/GCS_MAVLink/GCS_MAVLink.cpp +++ b/libraries/GCS_MAVLink/GCS_MAVLink.cpp @@ -144,7 +144,7 @@ void comm_send_buffer(mavlink_channel_t chan, const uint8_t *buf, uint8_t len) mavlink_comm_port[chan]->write(buf, len); } -static const uint8_t mavlink_message_crc_progmem[256] PROGMEM = MAVLINK_MESSAGE_CRCS; +static const uint8_t mavlink_message_crc_progmem[256] = MAVLINK_MESSAGE_CRCS; // return CRC byte for a mavlink message ID uint8_t mavlink_get_message_crc(uint8_t msgid) diff --git a/libraries/GCS_MAVLink/examples/routing/routing.cpp b/libraries/GCS_MAVLink/examples/routing/routing.cpp index 49d606b734..bf9c5876e6 100644 --- a/libraries/GCS_MAVLink/examples/routing/routing.cpp +++ b/libraries/GCS_MAVLink/examples/routing/routing.cpp @@ -15,7 +15,7 @@ static GCS_MAVLINK gcs[MAVLINK_COMM_NUM_BUFFERS]; extern mavlink_system_t mavlink_system; -const AP_Param::GroupInfo GCS_MAVLINK::var_info[] PROGMEM = { +const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = { AP_GROUPEND }; diff --git a/libraries/PID/PID.cpp b/libraries/PID/PID.cpp index 1991ae026a..28f88e8031 100644 --- a/libraries/PID/PID.cpp +++ b/libraries/PID/PID.cpp @@ -11,7 +11,7 @@ extern const AP_HAL::HAL& hal; -const AP_Param::GroupInfo PID::var_info[] PROGMEM = { +const AP_Param::GroupInfo PID::var_info[] = { AP_GROUPINFO("P", 0, PID, _kp, 0), AP_GROUPINFO("I", 1, PID, _ki, 0), AP_GROUPINFO("D", 2, PID, _kd, 0), diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index 517077ad15..8134b93f38 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -35,7 +35,7 @@ extern const AP_HAL::HAL& hal; /// only have 8 input channels. RC_Channel *RC_Channel::rc_ch[RC_MAX_CHANNELS]; -const AP_Param::GroupInfo RC_Channel::var_info[] PROGMEM = { +const AP_Param::GroupInfo RC_Channel::var_info[] = { // @Param: MIN // @DisplayName: RC min PWM // @Description: RC minimum PWM pulse width. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit. diff --git a/libraries/RC_Channel/RC_Channel_aux.cpp b/libraries/RC_Channel/RC_Channel_aux.cpp index d6d24f5815..5091d577a2 100644 --- a/libraries/RC_Channel/RC_Channel_aux.cpp +++ b/libraries/RC_Channel/RC_Channel_aux.cpp @@ -6,7 +6,7 @@ #include extern const AP_HAL::HAL& hal; -const AP_Param::GroupInfo RC_Channel_aux::var_info[] PROGMEM = { +const AP_Param::GroupInfo RC_Channel_aux::var_info[] = { AP_NESTEDGROUPINFO(RC_Channel, 0), // @Param: FUNCTION diff --git a/libraries/SITL/SITL.cpp b/libraries/SITL/SITL.cpp index bf076f6ffc..ee20ca2771 100644 --- a/libraries/SITL/SITL.cpp +++ b/libraries/SITL/SITL.cpp @@ -29,7 +29,7 @@ extern const AP_HAL::HAL& hal; namespace SITL { // table of user settable parameters -const AP_Param::GroupInfo SITL::var_info[] PROGMEM = { +const AP_Param::GroupInfo SITL::var_info[] = { AP_GROUPINFO("BARO_RND", 0, SITL, baro_noise, 0.2f), AP_GROUPINFO("GYR_RND", 1, SITL, gyro_noise, 0), AP_GROUPINFO("ACC_RND", 2, SITL, accel_noise, 0), diff --git a/libraries/StorageManager/StorageManager.cpp b/libraries/StorageManager/StorageManager.cpp index 1fd10dba74..9fe7695c11 100644 --- a/libraries/StorageManager/StorageManager.cpp +++ b/libraries/StorageManager/StorageManager.cpp @@ -36,7 +36,7 @@ extern const AP_HAL::HAL& hal; On PX4v1 this gives 309 waypoints, 30 rally points and 52 fence points On Pixhawk this gives 724 waypoints, 50 rally points and 84 fence points */ -const StorageManager::StorageArea StorageManager::layout_default[STORAGE_NUM_AREAS] PROGMEM = { +const StorageManager::StorageArea StorageManager::layout_default[STORAGE_NUM_AREAS] = { { StorageParam, 0, 1280}, // 0x500 parameter bytes { StorageMission, 1280, 2506}, { StorageRally, 3786, 150}, // 10 rally points @@ -63,7 +63,7 @@ const StorageManager::StorageArea StorageManager::layout_default[STORAGE_NUM_ARE On PX4v1 this gives 303 waypoints, 26 rally points and 38 fence points On Pixhawk this gives 718 waypoints, 46 rally points and 70 fence points */ -const StorageManager::StorageArea StorageManager::layout_copter[STORAGE_NUM_AREAS] PROGMEM = { +const StorageManager::StorageArea StorageManager::layout_copter[STORAGE_NUM_AREAS] = { { StorageParam, 0, 1536}, // 0x600 param bytes { StorageMission, 1536, 2422}, { StorageRally, 3958, 90}, // 6 rally points