23 #define GSCALAR(v, name, def) { copter.g.v.vtype, name, Parameters::k_param_ ## v, &copter.g.v, {def_value : def} } 24 #define ASCALAR(v, name, def) { copter.aparm.v.vtype, name, Parameters::k_param_ ## v, (const void *)&copter.aparm.v, {def_value : def} } 25 #define GGROUP(v, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, &copter.g.v, {group_info : class::var_info} } 26 #define GOBJECT(v, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, (const void *)&copter.v, {group_info : class::var_info} } 27 #define GOBJECTPTR(v, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, (const void *)&copter.v, {group_info : class::var_info}, AP_PARAM_FLAG_POINTER } 28 #define GOBJECTVARPTR(v, name, var_info_ptr) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, (const void *)&copter.v, {group_info_ptr : var_info_ptr}, AP_PARAM_FLAG_POINTER | AP_PARAM_FLAG_INFO_POINTER } 29 #define GOBJECTN(v, pname, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## pname, (const void *)&copter.v, {group_info : class::var_info} } 37 GSCALAR(format_version,
"SYSID_SW_MREV", 0),
59 GSCALAR(sysid_my_gcs,
"SYSID_MYGCS", 255),
68 GSCALAR(throttle_filt,
"PILOT_THR_FILT", 0),
93 GSCALAR(throttle_behavior,
"PILOT_THR_BHV", 0),
106 GSCALAR(telem_delay,
"TELEM_DELAY", 0),
114 GSCALAR(gcs_pid_mask,
"GCS_PID_MASK", 0),
116 #if MODE_RTL_ENABLED == ENABLED 142 GSCALAR(rtl_speed_cms,
"RTL_SPEED", 0),
172 #if RANGEFINDER_ENABLED == ENABLED 208 GSCALAR(super_simple,
"SUPER_SIMPLE", 0),
233 GSCALAR(land_speed_high,
"LAND_SPEED_HIGH", 0),
331 GSCALAR(simple_modes,
"SIMPLE", 0),
346 GSCALAR(esc_calibrate,
"ESC_CALIBRATION", 0),
353 GSCALAR(radio_tuning,
"TUNE", 0),
360 GSCALAR(radio_tuning_low,
"TUNE_LOW", 0),
367 GSCALAR(radio_tuning_high,
"TUNE_HIGH", 1000),
481 GSCALAR(fs_crash_check,
"FS_CRASH_CHECK", 1),
506 #if MODE_ACRO_ENABLED == ENABLED || MODE_SPORT_ENABLED == ENABLED 524 #if MODE_ACRO_ENABLED == ENABLED 543 #if CAMERA == ENABLED 553 #if PARACHUTE == ENABLED 563 #if FRAME_CONFIG == HELI_FRAME 585 #if MODE_CIRCLE_ENABLED == ENABLED 593 #if FRAME_CONFIG == HELI_FRAME 644 GOBJECT(BoardConfig_CAN,
"CAN_", AP_BoardConfig_CAN),
647 #if SPRAYER == ENABLED 653 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 670 #if AC_FENCE == ENABLED 678 #if AC_AVOID_ENABLED == ENABLED 682 #if AC_RALLY == ENABLED 688 #if FRAME_CONFIG == HELI_FRAME 710 #if MODE_AUTO_ENABLED == ENABLED 720 #if RANGEFINDER_ENABLED == ENABLED 726 #if AP_TERRAIN_AVAILABLE && AC_TERRAIN 729 GOBJECT(terrain,
"TERRAIN_", AP_Terrain),
732 #if OPTFLOW == ENABLED 738 #if PRECISION_LANDING == ENABLED 744 #if RPM_ENABLED == ENABLED 750 #if ADSB_ENABLED == ENABLED 760 #if AUTOTUNE_ENABLED == ENABLED 767 GSCALAR(autotune_axis_bitmask,
"AUTOTUNE_AXES", 7),
774 GSCALAR(autotune_aggressiveness,
"AUTOTUNE_AGGR", 0.1
f),
781 GSCALAR(autotune_min_d,
"AUTOTUNE_MIN_D", 0.001
f),
788 #if MODE_THROW_ENABLED == ENABLED 794 GSCALAR(throw_motor_start,
"THROW_MOT_START", 0),
797 #if AP_TERRAIN_AVAILABLE && AC_TERRAIN 803 GSCALAR(terrain_follow,
"TERRAIN_FOLLOW", 0),
829 #if MODE_THROW_ENABLED == ENABLED 852 #if ADVANCED_FAILSAFE == ENABLED 865 #if BEACON_ENABLED == ENABLED 871 #if PROXIMITY_ENABLED == ENABLED 885 #if MODE_ACRO_ENABLED == ENABLED 901 #if STATS_ENABLED == ENABLED 907 #if GRIPPER_ENABLED == ENABLED 929 #if VISUAL_ODOMETRY_ENABLED == ENABLED 939 #if TOY_MODE_ENABLED == ENABLED 945 #if MODE_SMARTRTL_ENABLED == ENABLED 951 #if WINCH_ENABLED == ENABLED 979 #if !HAL_MINIMIZE_FEATURES && OPTFLOW == ENABLED 985 #if MODE_FOLLOW_ENABLED == ENABLED 1004 , proximity(
copter.serial_manager)
1013 ,mode_flowhold_ptr(&
copter.mode_flowhold)
1064 if (!g.format_version.load() ||
1076 uint32_t before =
micros();
1101 #if FRAME_CONFIG == HELI_FRAME 1111 #if FRAME_CONFIG == HELI_FRAME 1150 float pid_scaler = 1.27f;
1152 #if FRAME_CONFIG != HELI_FRAME 1160 uint8_t table_size =
ARRAY_SIZE(pid_conversion_info);
1161 for (uint8_t i=0; i<table_size; i++) {
1165 table_size =
ARRAY_SIZE(imax_conversion_info);
1166 for (uint8_t i=0; i<table_size; i++) {
1170 table_size =
ARRAY_SIZE(angle_and_filt_conversion_info);
1171 for (uint8_t i=0; i<table_size; i++) {
1175 table_size =
ARRAY_SIZE(throttle_conversion_info);
1176 for (uint8_t i=0; i<table_size; i++) {
1181 AP_Int8 rc_feel_rp_old;
1186 table_size =
ARRAY_SIZE(loiter_conversion_info);
1187 for (uint8_t i=0; i<table_size; i++) {
1198 const uint16_t old_aux_chan_mask = 0x3FF0;
1202 upgrading_frame_params =
true;
#define WP_YAW_BEHAVIOR_DEFAULT
#define PILOT_TKOFF_ALT_DEFAULT
#define GOBJECTPTR(v, name, class)
#define DEFAULT_LOG_BITMASK
static const struct AP_Param::GroupInfo var_info[]
#define ACRO_THR_MID_DEFAULT
#define ACRO_BALANCE_ROLL
#define RTL_CONE_SLOPE_DEFAULT
#define ASCALAR(v, name, def)
static bool find_old_parameter(const struct ConversionInfo *info, AP_Param *value)
static bool upgrade_parameters(const uint8_t old_keys[14], uint16_t aux_channel_mask, RCMapper *rcmap)
AP_HAL::UARTDriver * console
void convert_pid_parameters(void)
static bool load_all(bool check_defaults_file=true)
#define POSHOLD_BRAKE_ANGLE_DEFAULT
#define AP_GROUPINFO(name, idx, clazz, element, def)
#define POSHOLD_BRAKE_RATE_DEFAULT
#define PROXIMITY_ENABLED
#define FS_EKF_ACTION_DEFAULT
static const AP_Param::Info var_info[]
const AP_Param::ConversionInfo conversion_table[]
#define GOBJECTN(v, pname, name, class)
static const uint16_t k_format_version
#define RANGEFINDER_GAIN_DEFAULT
AP_MotorsMatrix motors(400)
#define FS_EKF_THRESHOLD_DEFAULT
#define MODE_FOLLOW_ENABLED
#define FS_THR_VALUE_DEFAULT
virtual void printf(const char *,...) FMT_PRINTF(2
#define AP_SUBGROUPPTR(element, name, idx, thisclazz, elclazz)
void load_parameters(void)
static void erase_all(void)
void set_correct_centrifugal(bool setting)
#define FS_GCS_ENABLED_ALWAYS_RTL
#define PILOT_ACCEL_Z_DEFAULT
#define AUTO_DISARMING_DELAY
static void set_frame_type_flags(uint16_t flags_to_set)
#define HAL_MINIMIZE_FEATURES
AP_BattMonitor & battery()
#define ACRO_RP_EXPO_DEFAULT
#define FS_THR_ENABLED_ALWAYS_RTL
void set_soft_armed(const bool b)
DataFlash_Class DataFlash
AP_HAL_MAIN_CALLBACKS & copter
#define GOBJECT(v, name, class)
#define AP_PARAM_FRAME_COPTER
#define ACRO_BALANCE_PITCH
#define ADVANCED_FAILSAFE
#define LAND_REPOSITION_DEFAULT
static void convert_old_parameter(const struct ConversionInfo *info, float scaler, uint8_t flags=0)
static const uint16_t k_software_type
#define ACRO_TRAINER_LIMITED
#define RTL_CLIMB_MIN_DEFAULT
#define DEFAULT_ANGLE_MAX
AP_InertialSensor & ins()
#define MODE_SMARTRTL_ENABLED
void panic(const char *errormsg,...) FMT_PRINTF(1
#define AP_SUBGROUPINFO(element, name, idx, thisclazz, elclazz)
#define GOBJECTVARPTR(v, name, var_info_ptr)
#define ACRO_Y_EXPO_DEFAULT
#define GPS_HDOP_GOOD_DEFAULT
static void convert_old_parameters(const struct ConversionInfo *conversion_table, uint8_t table_size, uint8_t flags=0)
#define GSCALAR(v, name, def)
static bool check_var_info(void)
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
static bool set_default_by_name(const char *name, float value)