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.
This commit is contained in:
Lucas De Marchi 2015-10-25 15:03:46 -02:00 committed by Randy Mackay
parent d595e41003
commit 831d8acca5
104 changed files with 124 additions and 124 deletions

View File

@ -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),

View File

@ -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

View File

@ -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" },

View File

@ -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" },

View File

@ -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)}

View File

@ -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)},

View File

@ -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)},

View File

@ -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),

View File

@ -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

View File

@ -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),

View File

@ -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),

View File

@ -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

View File

@ -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),

View File

@ -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" },

View File

@ -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)},

View File

@ -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)},

View File

@ -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

View File

@ -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),

View File

@ -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

View File

@ -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" },

View File

@ -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" },

View File

@ -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),

View File

@ -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)},

View File

@ -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)},

View File

@ -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)},

View File

@ -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" }

View File

@ -5,7 +5,7 @@
#include <AP_Math/AP_Math.h>
// 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

View File

@ -4,7 +4,7 @@
#include <AP_HAL/AP_HAL.h>
// 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),

View File

@ -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

View File

@ -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

View File

@ -6,7 +6,7 @@
#include <AP_Math/AP_Math.h>
#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

View File

@ -6,7 +6,7 @@
#include <AP_Math/AP_Math.h>
#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

View File

@ -6,7 +6,7 @@
#include <AP_Math/AP_Math.h>
#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

View File

@ -6,7 +6,7 @@
#include <AP_Math/AP_Math.h>
#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

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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.

View File

@ -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.

View File

@ -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

View File

@ -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

View File

@ -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),

View File

@ -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

View File

@ -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

View File

@ -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.

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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}, \

View File

@ -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

View File

@ -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

View File

@ -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),

View File

@ -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 //////////////////////////////////////////////////////////
//

View File

@ -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),

View File

@ -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
};

View File

@ -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,

View File

@ -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)},

View File

@ -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).

View File

@ -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
};

View File

@ -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.

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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,

View File

@ -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__

View File

@ -6,7 +6,7 @@
#include "AP_Mission.h"
#include <AP_Terrain/AP_Terrain.h>
const AP_Param::GroupInfo AP_Mission::var_info[] PROGMEM = {
const AP_Param::GroupInfo AP_Mission::var_info[] = {
// @Param: TOTAL
// @DisplayName: Total mission commands

View File

@ -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),

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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),

View File

@ -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),

View File

@ -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

View File

@ -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

View File

@ -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
};

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -3,7 +3,7 @@
#include <AP_HAL/AP_HAL.h>
#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.

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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.

View File

@ -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.

View File

@ -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),

View File

@ -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.

View File

@ -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)

View File

@ -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.

View File

@ -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" }

View File

@ -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)

View File

@ -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
};

View File

@ -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),

Some files were not shown because too many files have changed in this diff Show More