|
|
|
@ -20,11 +20,13 @@ public:
@@ -20,11 +20,13 @@ public:
|
|
|
|
|
static const uint16_t k_format_version = 118; |
|
|
|
|
|
|
|
|
|
// The parameter software_type is set up solely for ground station use
|
|
|
|
|
// and identifies the software type (eg ArduPilotMega versus ArduCopterMega)
|
|
|
|
|
// and identifies the software type (eg ArduPilotMega versus
|
|
|
|
|
// ArduCopterMega)
|
|
|
|
|
// GCS will interpret values 0-9 as ArduPilotMega. Developers may use
|
|
|
|
|
// values within that range to identify different branches.
|
|
|
|
|
//
|
|
|
|
|
static const uint16_t k_software_type = 10; // 0 for APM trunk
|
|
|
|
|
static const uint16_t k_software_type = 10; // 0 for APM
|
|
|
|
|
// trunk
|
|
|
|
|
|
|
|
|
|
// Parameter identities.
|
|
|
|
|
//
|
|
|
|
@ -58,8 +60,13 @@ public:
@@ -58,8 +60,13 @@ public:
|
|
|
|
|
// Misc
|
|
|
|
|
//
|
|
|
|
|
k_param_log_bitmask = 20, |
|
|
|
|
k_param_log_last_filenumber, // *** Deprecated - remove with next eeprom number change
|
|
|
|
|
k_param_toy_yaw_rate, // THOR The memory location for the Yaw Rate 1 = fast, 2 = med, 3 = slow
|
|
|
|
|
k_param_log_last_filenumber, // *** Deprecated - remove
|
|
|
|
|
// with next eeprom number
|
|
|
|
|
// change
|
|
|
|
|
k_param_toy_yaw_rate, // THOR The memory
|
|
|
|
|
// location for the
|
|
|
|
|
// Yaw Rate 1 = fast,
|
|
|
|
|
// 2 = med, 3 = slow
|
|
|
|
|
|
|
|
|
|
// 65: AP_Limits Library
|
|
|
|
|
k_param_limits = 65, |
|
|
|
@ -218,11 +225,13 @@ public:
@@ -218,11 +225,13 @@ public:
|
|
|
|
|
AP_Int8 sonar_type; // 0 = XL, 1 = LV,
|
|
|
|
|
// 2 = XLL (XL with 10m range)
|
|
|
|
|
// 3 = HRLV
|
|
|
|
|
AP_Int8 battery_monitoring; // 0=disabled, 3=voltage only, 4=voltage and current
|
|
|
|
|
AP_Int8 battery_monitoring; // 0=disabled, 3=voltage only,
|
|
|
|
|
// 4=voltage and current
|
|
|
|
|
AP_Float volt_div_ratio; |
|
|
|
|
AP_Float curr_amp_per_volt; |
|
|
|
|
AP_Float input_voltage; |
|
|
|
|
AP_Int16 pack_capacity; // Battery pack capacity less reserve
|
|
|
|
|
AP_Int16 pack_capacity; // Battery pack capacity less
|
|
|
|
|
// reserve
|
|
|
|
|
AP_Int8 compass_enabled; |
|
|
|
|
AP_Int8 optflow_enabled; |
|
|
|
|
AP_Float low_voltage; |
|
|
|
@ -230,7 +239,8 @@ public:
@@ -230,7 +239,8 @@ public:
|
|
|
|
|
AP_Int16 rtl_approach_alt; |
|
|
|
|
AP_Int8 tilt_comp; |
|
|
|
|
AP_Int8 axis_enabled; |
|
|
|
|
AP_Int8 copter_leds_mode; // Operating mode of LED lighting system
|
|
|
|
|
AP_Int8 copter_leds_mode; // Operating mode of LED
|
|
|
|
|
// lighting system
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
@ -269,8 +279,14 @@ public:
@@ -269,8 +279,14 @@ public:
|
|
|
|
|
// Misc
|
|
|
|
|
//
|
|
|
|
|
AP_Int16 log_bitmask; |
|
|
|
|
AP_Int16 log_last_filenumber; // *** Deprecated - remove with next eeprom number change
|
|
|
|
|
AP_Int8 toy_yaw_rate; // THOR The Yaw Rate 1 = fast, 2 = med, 3 = slow
|
|
|
|
|
AP_Int16 log_last_filenumber; // *** Deprecated - remove
|
|
|
|
|
// with next eeprom number
|
|
|
|
|
// change
|
|
|
|
|
AP_Int8 toy_yaw_rate; // THOR The
|
|
|
|
|
// Yaw Rate 1
|
|
|
|
|
// = fast, 2 =
|
|
|
|
|
// med, 3 =
|
|
|
|
|
// slow
|
|
|
|
|
AP_Int8 esc_calibrate; |
|
|
|
|
AP_Int8 radio_tuning; |
|
|
|
|
AP_Int16 radio_tuning_high; |
|
|
|
@ -279,10 +295,16 @@ public:
@@ -279,10 +295,16 @@ public:
|
|
|
|
|
AP_Int8 ch7_option; |
|
|
|
|
AP_Int16 auto_slew_rate; |
|
|
|
|
|
|
|
|
|
#if FRAME_CONFIG == HELI_FRAME |
|
|
|
|
#if FRAME_CONFIG == HELI_FRAME |
|
|
|
|
// Heli
|
|
|
|
|
RC_Channel heli_servo_1, heli_servo_2, heli_servo_3, heli_servo_4; // servos for swash plate and tail
|
|
|
|
|
#endif |
|
|
|
|
RC_Channel heli_servo_1, heli_servo_2, heli_servo_3, heli_servo_4; //
|
|
|
|
|
// servos
|
|
|
|
|
// for
|
|
|
|
|
// swash
|
|
|
|
|
// plate
|
|
|
|
|
// and
|
|
|
|
|
// tail
|
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
// Camera
|
|
|
|
|
#if CAMERA == ENABLED |
|
|
|
@ -332,7 +354,8 @@ public:
@@ -332,7 +354,8 @@ public:
|
|
|
|
|
APM_PI pi_stabilize_yaw; |
|
|
|
|
APM_PI pi_alt_hold; |
|
|
|
|
|
|
|
|
|
// Note: keep initializers here in the same order as they are declared above.
|
|
|
|
|
// Note: keep initializers here in the same order as they are declared
|
|
|
|
|
// above.
|
|
|
|
|
Parameters() : |
|
|
|
|
|
|
|
|
|
#if FRAME_CONFIG == HELI_FRAME |
|
|
|
@ -356,7 +379,8 @@ public:
@@ -356,7 +379,8 @@ public:
|
|
|
|
|
rc_11 (CH_11), |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
// PID controller initial P initial I initial D initial imax
|
|
|
|
|
// PID controller initial P initial I initial D
|
|
|
|
|
// initial imax
|
|
|
|
|
//-----------------------------------------------------------------------------------------------------
|
|
|
|
|
pid_rate_roll (RATE_ROLL_P, RATE_ROLL_I, RATE_ROLL_D, RATE_ROLL_IMAX * 100), |
|
|
|
|
pid_rate_pitch (RATE_PITCH_P, RATE_PITCH_I, RATE_PITCH_D, RATE_PITCH_IMAX * 100), |
|
|
|
@ -372,7 +396,8 @@ public:
@@ -372,7 +396,8 @@ public:
|
|
|
|
|
pid_optflow_roll (OPTFLOW_ROLL_P, OPTFLOW_ROLL_I, OPTFLOW_ROLL_D, OPTFLOW_IMAX * 100), |
|
|
|
|
pid_optflow_pitch (OPTFLOW_PITCH_P, OPTFLOW_PITCH_I, OPTFLOW_PITCH_D, OPTFLOW_IMAX * 100), |
|
|
|
|
|
|
|
|
|
// PI controller initial P initial I initial imax
|
|
|
|
|
// PI controller initial P initial I initial
|
|
|
|
|
// imax
|
|
|
|
|
//----------------------------------------------------------------------
|
|
|
|
|
pi_loiter_lat (LOITER_P, LOITER_I, LOITER_IMAX * 100), |
|
|
|
|
pi_loiter_lon (LOITER_P, LOITER_I, LOITER_IMAX * 100), |
|
|
|
|