2011-02-17 03:09:13 -04:00
|
|
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
|
|
|
|
|
|
#ifndef PARAMETERS_H
|
|
|
|
#define PARAMETERS_H
|
|
|
|
|
|
|
|
#include <AP_Common.h>
|
|
|
|
|
|
|
|
// Global parameter class.
|
|
|
|
//
|
|
|
|
class Parameters {
|
|
|
|
public:
|
2011-07-10 21:47:08 -03:00
|
|
|
// The version of the layout as described by the parameter enum.
|
|
|
|
//
|
|
|
|
// When changing the parameter enum in an incompatible fashion, this
|
|
|
|
// value should be incremented by one.
|
|
|
|
//
|
|
|
|
// The increment will prevent old parameters from being used incorrectly
|
|
|
|
// by newer code.
|
|
|
|
//
|
2012-04-04 10:55:07 -03:00
|
|
|
static const uint16_t k_format_version = 118;
|
2011-06-16 14:03:26 -03:00
|
|
|
|
|
|
|
// The parameter software_type is set up solely for ground station use
|
|
|
|
// and identifies the software type (eg ArduPilotMega versus ArduCopterMega)
|
2011-11-05 01:41:51 -03:00
|
|
|
// GCS will interpret values 0-9 as ArduPilotMega. Developers may use
|
2011-06-16 14:03:26 -03:00
|
|
|
// values within that range to identify different branches.
|
|
|
|
//
|
2011-07-10 21:47:08 -03:00
|
|
|
static const uint16_t k_software_type = 10; // 0 for APM trunk
|
|
|
|
|
|
|
|
// Parameter identities.
|
|
|
|
//
|
|
|
|
// The enumeration defined here is used to ensure that every parameter
|
|
|
|
// or parameter group has a unique ID number. This number is used by
|
|
|
|
// AP_Var to store and locate parameters in EEPROM.
|
|
|
|
//
|
|
|
|
// Note that entries without a number are assigned the next number after
|
|
|
|
// the entry preceding them. When adding new entries, ensure that they
|
|
|
|
// don't overlap.
|
|
|
|
//
|
|
|
|
// Try to group related variables together, and assign them a set
|
|
|
|
// range in the enumeration. Place these groups in numerical order
|
|
|
|
// at the end of the enumeration.
|
|
|
|
//
|
|
|
|
// WARNING: Care should be taken when editing this enumeration as the
|
|
|
|
// AP_Var load/save code depends on the values here to identify
|
|
|
|
// variables saved in EEPROM.
|
|
|
|
//
|
|
|
|
//
|
|
|
|
enum {
|
|
|
|
// Layout version number, always key zero.
|
|
|
|
//
|
|
|
|
k_param_format_version = 0,
|
|
|
|
k_param_software_type,
|
|
|
|
|
|
|
|
|
|
|
|
// Misc
|
|
|
|
//
|
2011-11-19 18:00:23 -04:00
|
|
|
k_param_log_bitmask = 20,
|
2011-12-13 23:06:46 -04:00
|
|
|
k_param_log_last_filenumber, // *** Deprecated - remove with next eeprom number change
|
2011-07-10 21:47:08 -03:00
|
|
|
|
2011-09-25 04:51:25 -03:00
|
|
|
#if FRAME_CONFIG == HELI_FRAME
|
|
|
|
//
|
|
|
|
// 80: Heli
|
|
|
|
//
|
|
|
|
k_param_heli_servo_1 = 80,
|
|
|
|
k_param_heli_servo_2,
|
|
|
|
k_param_heli_servo_3,
|
|
|
|
k_param_heli_servo_4,
|
|
|
|
#endif
|
2011-09-25 16:24:02 -03:00
|
|
|
|
2012-04-04 10:55:07 -03:00
|
|
|
//
|
|
|
|
// 90: Motors
|
|
|
|
//
|
|
|
|
k_param_motors = 90,
|
|
|
|
|
2011-07-10 21:47:08 -03:00
|
|
|
// 110: Telemetry control
|
|
|
|
//
|
2012-02-12 07:26:36 -04:00
|
|
|
k_param_gcs0 = 110,
|
|
|
|
k_param_gcs3,
|
2011-07-10 21:47:08 -03:00
|
|
|
k_param_sysid_this_mav,
|
|
|
|
k_param_sysid_my_gcs,
|
2011-08-01 08:39:17 -03:00
|
|
|
k_param_serial3_baud,
|
2011-07-10 21:47:08 -03:00
|
|
|
|
|
|
|
//
|
|
|
|
// 140: Sensor parameters
|
|
|
|
//
|
2012-02-17 19:39:57 -04:00
|
|
|
k_param_imu = 140, // sensor calibration
|
2012-01-20 18:29:09 -04:00
|
|
|
k_param_battery_monitoring,
|
|
|
|
k_param_volt_div_ratio,
|
|
|
|
k_param_curr_amp_per_volt,
|
|
|
|
k_param_input_voltage,
|
2011-07-10 21:47:08 -03:00
|
|
|
k_param_pack_capacity,
|
|
|
|
k_param_compass_enabled,
|
|
|
|
k_param_compass,
|
2012-02-12 07:26:36 -04:00
|
|
|
k_param_sonar_enabled,
|
2011-07-10 21:47:08 -03:00
|
|
|
k_param_frame_orientation,
|
2011-07-21 20:14:53 -03:00
|
|
|
k_param_optflow_enabled,
|
2011-09-16 22:56:51 -03:00
|
|
|
k_param_low_voltage,
|
2011-11-26 17:19:11 -04:00
|
|
|
k_param_ch7_option,
|
2012-02-15 13:05:17 -04:00
|
|
|
k_param_auto_slew_rate,
|
2012-01-22 02:13:57 -04:00
|
|
|
k_param_sonar_type,
|
2012-04-04 10:55:07 -03:00
|
|
|
k_param_super_simple,
|
2012-02-15 13:05:17 -04:00
|
|
|
k_param_rtl_land_enabled,
|
2012-04-12 10:50:28 -03:00
|
|
|
k_param_axis_enabled,
|
|
|
|
k_param_copter_leds_mode, //158
|
2012-04-16 07:55:03 -03:00
|
|
|
k_param_ahrs, // AHRS group
|
2011-07-10 21:47:08 -03:00
|
|
|
|
|
|
|
//
|
|
|
|
// 160: Navigation parameters
|
|
|
|
//
|
2011-11-19 18:00:23 -04:00
|
|
|
k_param_RTL_altitude = 160,
|
|
|
|
k_param_crosstrack_gain,
|
2012-01-20 20:49:36 -04:00
|
|
|
k_param_auto_land_timeout,
|
2012-04-16 12:23:01 -03:00
|
|
|
k_param_rtl_approach_alt,
|
2012-01-20 20:49:36 -04:00
|
|
|
|
2011-07-10 21:47:08 -03:00
|
|
|
|
|
|
|
//
|
2012-03-02 00:45:43 -04:00
|
|
|
// 170: Radio settings
|
2011-07-10 21:47:08 -03:00
|
|
|
//
|
2012-03-02 00:45:43 -04:00
|
|
|
k_param_rc_1 = 170,
|
2011-07-10 21:47:08 -03:00
|
|
|
k_param_rc_2,
|
|
|
|
k_param_rc_3,
|
|
|
|
k_param_rc_4,
|
|
|
|
k_param_rc_5,
|
|
|
|
k_param_rc_6,
|
|
|
|
k_param_rc_7,
|
|
|
|
k_param_rc_8,
|
2012-02-12 07:26:36 -04:00
|
|
|
k_param_rc_camera_pitch,// rc_9
|
|
|
|
k_param_rc_camera_roll, // rc_10
|
2011-07-10 21:47:08 -03:00
|
|
|
k_param_throttle_min,
|
|
|
|
k_param_throttle_max,
|
|
|
|
k_param_throttle_fs_enabled,
|
|
|
|
k_param_throttle_fs_action,
|
|
|
|
k_param_throttle_fs_value,
|
|
|
|
k_param_throttle_cruise,
|
|
|
|
k_param_esc_calibrate,
|
2011-09-10 19:16:51 -03:00
|
|
|
k_param_radio_tuning,
|
2012-02-15 13:04:12 -04:00
|
|
|
k_param_radio_tuning_high,
|
|
|
|
k_param_radio_tuning_low,
|
2011-10-15 20:34:57 -03:00
|
|
|
k_param_camera_pitch_gain,
|
|
|
|
k_param_camera_roll_gain,
|
2012-03-02 02:24:18 -04:00
|
|
|
k_param_rc_speed,
|
2011-07-12 17:04:15 -03:00
|
|
|
|
2011-07-17 07:30:53 -03:00
|
|
|
//
|
2012-02-15 13:04:12 -04:00
|
|
|
// 200: flight modes
|
2011-07-17 07:30:53 -03:00
|
|
|
//
|
2012-02-15 13:04:12 -04:00
|
|
|
k_param_flight_mode1 = 200,
|
2011-07-17 07:30:53 -03:00
|
|
|
k_param_flight_mode2,
|
|
|
|
k_param_flight_mode3,
|
|
|
|
k_param_flight_mode4,
|
|
|
|
k_param_flight_mode5,
|
|
|
|
k_param_flight_mode6,
|
2011-09-14 17:58:18 -03:00
|
|
|
k_param_simple_modes,
|
2011-07-17 07:30:53 -03:00
|
|
|
|
2011-07-10 21:47:08 -03:00
|
|
|
//
|
2012-02-15 13:04:12 -04:00
|
|
|
// 210: Waypoint data
|
2011-07-10 21:47:08 -03:00
|
|
|
//
|
2012-02-15 13:04:12 -04:00
|
|
|
k_param_waypoint_mode = 210,
|
2011-11-05 01:41:51 -03:00
|
|
|
k_param_command_total,
|
|
|
|
k_param_command_index,
|
2011-11-16 04:19:29 -04:00
|
|
|
k_param_command_nav_index,
|
2011-07-10 21:47:08 -03:00
|
|
|
k_param_waypoint_radius,
|
|
|
|
k_param_loiter_radius,
|
|
|
|
k_param_waypoint_speed_max,
|
|
|
|
|
|
|
|
//
|
2012-02-15 13:04:12 -04:00
|
|
|
// 220: PI/D Controllers
|
2011-07-10 21:47:08 -03:00
|
|
|
//
|
2012-02-29 00:13:36 -04:00
|
|
|
k_param_stabilize_d_schedule = 219,
|
2012-02-15 13:04:12 -04:00
|
|
|
k_param_stabilize_d = 220,
|
2012-02-15 15:29:25 -04:00
|
|
|
k_param_acro_p,
|
2012-02-19 01:13:06 -04:00
|
|
|
k_param_axis_lock_p,
|
2012-02-15 13:04:12 -04:00
|
|
|
k_param_pid_rate_roll,
|
2012-01-29 02:00:05 -04:00
|
|
|
k_param_pid_rate_pitch,
|
|
|
|
k_param_pid_rate_yaw,
|
2011-09-04 21:15:36 -03:00
|
|
|
k_param_pi_stabilize_roll,
|
|
|
|
k_param_pi_stabilize_pitch,
|
|
|
|
k_param_pi_stabilize_yaw,
|
|
|
|
k_param_pi_loiter_lat,
|
|
|
|
k_param_pi_loiter_lon,
|
2012-02-15 13:05:17 -04:00
|
|
|
k_param_pid_loiter_rate_lat,
|
|
|
|
k_param_pid_loiter_rate_lon,
|
2012-01-29 02:00:05 -04:00
|
|
|
k_param_pid_nav_lat,
|
|
|
|
k_param_pid_nav_lon,
|
2011-10-02 15:36:23 -03:00
|
|
|
k_param_pi_alt_hold,
|
2012-01-29 02:00:05 -04:00
|
|
|
k_param_pid_throttle,
|
|
|
|
k_param_pid_optflow_roll,
|
2012-02-15 13:04:12 -04:00
|
|
|
k_param_pid_optflow_pitch,
|
2011-07-10 21:47:08 -03:00
|
|
|
|
2011-09-04 03:42:36 -03:00
|
|
|
// 254,255: reserved
|
2011-07-10 21:47:08 -03:00
|
|
|
};
|
|
|
|
|
|
|
|
AP_Int16 format_version;
|
2011-06-16 14:03:26 -03:00
|
|
|
AP_Int8 software_type;
|
|
|
|
|
|
|
|
// Telemetry control
|
|
|
|
//
|
2011-07-10 21:47:08 -03:00
|
|
|
AP_Int16 sysid_this_mav;
|
|
|
|
AP_Int16 sysid_my_gcs;
|
2011-09-14 17:58:18 -03:00
|
|
|
AP_Int8 serial3_baud;
|
2011-07-10 21:47:08 -03:00
|
|
|
|
|
|
|
|
2011-11-19 18:00:23 -04:00
|
|
|
AP_Int16 RTL_altitude;
|
|
|
|
AP_Int8 sonar_enabled;
|
2011-12-11 03:40:59 -04:00
|
|
|
AP_Int8 sonar_type; // 0 = XL, 1 = LV, 2 = XLL (XL with 10m range)
|
2012-01-20 18:29:09 -04:00
|
|
|
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;
|
2011-11-19 18:00:23 -04:00
|
|
|
AP_Int16 pack_capacity; // Battery pack capacity less reserve
|
|
|
|
AP_Int8 compass_enabled;
|
|
|
|
AP_Int8 optflow_enabled;
|
|
|
|
AP_Float low_voltage;
|
2011-12-16 00:46:12 -04:00
|
|
|
AP_Int8 super_simple;
|
2012-02-15 13:05:17 -04:00
|
|
|
AP_Int8 rtl_land_enabled;
|
2012-04-16 12:06:29 -03:00
|
|
|
AP_Float rtl_approach_alt;
|
2012-02-19 01:13:06 -04:00
|
|
|
AP_Int8 axis_enabled;
|
2012-04-12 10:50:28 -03:00
|
|
|
AP_Int8 copter_leds_mode; // Operating mode of LED lighting system
|
2012-02-19 01:13:06 -04:00
|
|
|
|
2011-12-12 14:20:15 -04:00
|
|
|
|
2011-07-10 21:47:08 -03:00
|
|
|
|
|
|
|
// Waypoints
|
|
|
|
//
|
|
|
|
AP_Int8 waypoint_mode;
|
2011-11-05 01:41:51 -03:00
|
|
|
AP_Int8 command_total;
|
|
|
|
AP_Int8 command_index;
|
2011-11-16 04:19:29 -04:00
|
|
|
AP_Int8 command_nav_index;
|
2011-07-10 21:47:08 -03:00
|
|
|
AP_Int8 waypoint_radius;
|
2011-11-12 19:15:33 -04:00
|
|
|
AP_Int16 loiter_radius;
|
2011-07-10 21:47:08 -03:00
|
|
|
AP_Int16 waypoint_speed_max;
|
2011-11-19 18:00:23 -04:00
|
|
|
AP_Float crosstrack_gain;
|
2012-01-20 20:49:36 -04:00
|
|
|
AP_Int32 auto_land_timeout;
|
|
|
|
|
2011-07-10 21:47:08 -03:00
|
|
|
|
|
|
|
// Throttle
|
|
|
|
//
|
|
|
|
AP_Int16 throttle_min;
|
|
|
|
AP_Int16 throttle_max;
|
|
|
|
AP_Int8 throttle_fs_enabled;
|
|
|
|
AP_Int8 throttle_fs_action;
|
|
|
|
AP_Int16 throttle_fs_value;
|
|
|
|
AP_Int16 throttle_cruise;
|
|
|
|
|
|
|
|
// Flight modes
|
|
|
|
//
|
2011-07-17 07:30:53 -03:00
|
|
|
AP_Int8 flight_mode1;
|
|
|
|
AP_Int8 flight_mode2;
|
|
|
|
AP_Int8 flight_mode3;
|
|
|
|
AP_Int8 flight_mode4;
|
|
|
|
AP_Int8 flight_mode5;
|
|
|
|
AP_Int8 flight_mode6;
|
2011-09-14 17:58:18 -03:00
|
|
|
AP_Int8 simple_modes;
|
2011-07-10 21:47:08 -03:00
|
|
|
|
|
|
|
// Misc
|
|
|
|
//
|
|
|
|
AP_Int16 log_bitmask;
|
2011-12-13 23:06:46 -04:00
|
|
|
AP_Int16 log_last_filenumber; // *** Deprecated - remove with next eeprom number change
|
2011-07-10 21:47:08 -03:00
|
|
|
|
2011-05-06 19:46:57 -03:00
|
|
|
AP_Int8 esc_calibrate;
|
2011-09-10 19:16:51 -03:00
|
|
|
AP_Int8 radio_tuning;
|
2012-02-15 13:04:12 -04:00
|
|
|
AP_Int16 radio_tuning_high;
|
|
|
|
AP_Int16 radio_tuning_low;
|
2011-05-18 20:38:24 -03:00
|
|
|
AP_Int8 frame_orientation;
|
2011-11-26 17:19:11 -04:00
|
|
|
AP_Int8 ch7_option;
|
2012-02-15 13:05:17 -04:00
|
|
|
AP_Int16 auto_slew_rate;
|
2011-02-17 03:09:13 -04:00
|
|
|
|
2011-07-10 21:47:08 -03:00
|
|
|
#if FRAME_CONFIG == HELI_FRAME
|
2011-06-12 09:14:10 -03:00
|
|
|
// Heli
|
2011-07-10 21:47:08 -03:00
|
|
|
RC_Channel heli_servo_1, heli_servo_2, heli_servo_3, heli_servo_4; // servos for swash plate and tail
|
2011-06-16 14:03:26 -03:00
|
|
|
#endif
|
|
|
|
|
2011-09-04 21:15:36 -03:00
|
|
|
// RC channels
|
2011-02-17 03:09:13 -04:00
|
|
|
RC_Channel rc_1;
|
|
|
|
RC_Channel rc_2;
|
|
|
|
RC_Channel rc_3;
|
|
|
|
RC_Channel rc_4;
|
|
|
|
RC_Channel rc_5;
|
|
|
|
RC_Channel rc_6;
|
|
|
|
RC_Channel rc_7;
|
2011-02-17 05:36:33 -04:00
|
|
|
RC_Channel rc_8;
|
2011-02-17 03:09:13 -04:00
|
|
|
RC_Channel rc_camera_pitch;
|
|
|
|
RC_Channel rc_camera_roll;
|
2012-03-02 02:24:18 -04:00
|
|
|
AP_Int16 rc_speed; // speed of fast RC Channels in Hz
|
2011-11-19 18:00:23 -04:00
|
|
|
|
2011-10-15 20:34:57 -03:00
|
|
|
AP_Float camera_pitch_gain;
|
|
|
|
AP_Float camera_roll_gain;
|
2012-02-12 07:26:36 -04:00
|
|
|
AP_Float stabilize_d;
|
2012-02-29 00:13:36 -04:00
|
|
|
AP_Float stabilize_d_schedule;
|
2011-02-17 03:09:13 -04:00
|
|
|
|
2011-09-04 21:15:36 -03:00
|
|
|
// PI/D controllers
|
2012-02-15 15:29:25 -04:00
|
|
|
AP_Float acro_p;
|
2012-02-19 01:13:06 -04:00
|
|
|
AP_Float axis_lock_p;
|
2012-02-15 13:05:17 -04:00
|
|
|
|
2012-01-29 02:00:05 -04:00
|
|
|
AC_PID pid_rate_roll;
|
|
|
|
AC_PID pid_rate_pitch;
|
|
|
|
AC_PID pid_rate_yaw;
|
2012-02-15 13:05:17 -04:00
|
|
|
AC_PID pid_loiter_rate_lat;
|
|
|
|
AC_PID pid_loiter_rate_lon;
|
2012-01-29 02:00:05 -04:00
|
|
|
AC_PID pid_nav_lat;
|
|
|
|
AC_PID pid_nav_lon;
|
2011-09-04 21:15:36 -03:00
|
|
|
|
2012-01-29 02:00:05 -04:00
|
|
|
AC_PID pid_throttle;
|
|
|
|
AC_PID pid_optflow_roll;
|
|
|
|
AC_PID pid_optflow_pitch;
|
2011-09-04 21:15:36 -03:00
|
|
|
|
|
|
|
APM_PI pi_loiter_lat;
|
|
|
|
APM_PI pi_loiter_lon;
|
2012-01-29 02:00:05 -04:00
|
|
|
APM_PI pi_stabilize_roll;
|
|
|
|
APM_PI pi_stabilize_pitch;
|
|
|
|
APM_PI pi_stabilize_yaw;
|
2011-10-02 15:36:23 -03:00
|
|
|
APM_PI pi_alt_hold;
|
2012-01-09 00:53:54 -04:00
|
|
|
|
2011-07-10 21:47:08 -03:00
|
|
|
// Note: keep initializers here in the same order as they are declared above.
|
|
|
|
Parameters() :
|
2012-02-12 07:26:36 -04:00
|
|
|
// variable default
|
|
|
|
//----------------------------------------
|
|
|
|
format_version (k_format_version),
|
|
|
|
software_type (k_software_type),
|
|
|
|
|
|
|
|
sysid_this_mav (MAV_SYSTEM_ID),
|
|
|
|
sysid_my_gcs (255),
|
|
|
|
serial3_baud (SERIAL3_BAUD/1000),
|
|
|
|
|
|
|
|
RTL_altitude (ALT_HOLD_HOME * 100),
|
|
|
|
sonar_enabled (DISABLED),
|
|
|
|
sonar_type (AP_RANGEFINDER_MAXSONARXL),
|
|
|
|
battery_monitoring (DISABLED),
|
|
|
|
volt_div_ratio (VOLT_DIV_RATIO),
|
|
|
|
curr_amp_per_volt (CURR_AMP_PER_VOLT),
|
|
|
|
input_voltage (INPUT_VOLTAGE),
|
|
|
|
pack_capacity (HIGH_DISCHARGE),
|
|
|
|
compass_enabled (MAGNETOMETER),
|
|
|
|
optflow_enabled (OPTFLOW),
|
|
|
|
low_voltage (LOW_VOLTAGE),
|
|
|
|
super_simple (SUPER_SIMPLE),
|
2012-02-15 13:05:17 -04:00
|
|
|
rtl_land_enabled (RTL_AUTO_LAND),
|
2012-04-16 12:06:29 -03:00
|
|
|
rtl_approach_alt (0.0),
|
2012-02-19 01:13:06 -04:00
|
|
|
axis_enabled (AXIS_LOCK_ENABLED),
|
2012-04-12 10:50:28 -03:00
|
|
|
copter_leds_mode (0),
|
2012-02-12 07:26:36 -04:00
|
|
|
|
|
|
|
waypoint_mode (0),
|
|
|
|
command_total (0),
|
|
|
|
command_index (0),
|
|
|
|
command_nav_index (0),
|
|
|
|
waypoint_radius (WP_RADIUS_DEFAULT * 100),
|
|
|
|
loiter_radius (LOITER_RADIUS),
|
|
|
|
waypoint_speed_max (WAYPOINT_SPEED_MAX),
|
|
|
|
crosstrack_gain (CROSSTRACK_GAIN),
|
|
|
|
auto_land_timeout (AUTO_LAND_TIME * 1000),
|
|
|
|
|
|
|
|
throttle_min (0),
|
|
|
|
throttle_max (1000),
|
|
|
|
throttle_fs_enabled (THROTTLE_FAILSAFE),
|
|
|
|
throttle_fs_action (THROTTLE_FAILSAFE_ACTION),
|
|
|
|
throttle_fs_value (THROTTLE_FS_VALUE),
|
|
|
|
throttle_cruise (THROTTLE_CRUISE),
|
|
|
|
|
|
|
|
flight_mode1 (FLIGHT_MODE_1),
|
|
|
|
flight_mode2 (FLIGHT_MODE_2),
|
|
|
|
flight_mode3 (FLIGHT_MODE_3),
|
|
|
|
flight_mode4 (FLIGHT_MODE_4),
|
|
|
|
flight_mode5 (FLIGHT_MODE_5),
|
|
|
|
flight_mode6 (FLIGHT_MODE_6),
|
|
|
|
simple_modes (0),
|
|
|
|
|
|
|
|
log_bitmask (DEFAULT_LOG_BITMASK),
|
|
|
|
log_last_filenumber (0),
|
|
|
|
esc_calibrate (0),
|
|
|
|
radio_tuning (0),
|
2012-02-15 13:04:12 -04:00
|
|
|
radio_tuning_high (1000),
|
|
|
|
radio_tuning_low (0),
|
2012-02-12 07:26:36 -04:00
|
|
|
frame_orientation (FRAME_ORIENTATION),
|
|
|
|
ch7_option (CH7_OPTION),
|
2012-02-15 13:05:17 -04:00
|
|
|
auto_slew_rate (AUTO_SLEW_RATE),
|
2011-07-10 21:47:08 -03:00
|
|
|
|
2012-03-02 02:24:18 -04:00
|
|
|
rc_speed(RC_FAST_SPEED),
|
|
|
|
|
2012-02-12 07:26:36 -04:00
|
|
|
camera_pitch_gain (CAM_PITCH_GAIN),
|
|
|
|
camera_roll_gain (CAM_ROLL_GAIN),
|
|
|
|
stabilize_d (STABILIZE_D),
|
2012-02-29 00:13:36 -04:00
|
|
|
stabilize_d_schedule (STABILIZE_D_SCHEDULE),
|
2012-02-15 15:29:25 -04:00
|
|
|
acro_p (ACRO_P),
|
2012-02-19 01:13:06 -04:00
|
|
|
axis_lock_p (AXIS_LOCK_P),
|
2012-02-12 07:26:36 -04:00
|
|
|
|
2012-02-15 13:05:17 -04:00
|
|
|
// 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),
|
|
|
|
pid_rate_yaw (RATE_YAW_P, RATE_YAW_I, RATE_YAW_D, RATE_YAW_IMAX * 100),
|
|
|
|
|
|
|
|
pid_loiter_rate_lat (LOITER_RATE_P, LOITER_RATE_I, LOITER_RATE_D, LOITER_RATE_IMAX * 100),
|
|
|
|
pid_loiter_rate_lon (LOITER_RATE_P, LOITER_RATE_I, LOITER_RATE_D, LOITER_RATE_IMAX * 100),
|
2012-02-12 07:26:36 -04:00
|
|
|
|
2012-02-15 13:05:17 -04:00
|
|
|
pid_nav_lat (NAV_P, NAV_I, NAV_D, NAV_IMAX * 100),
|
|
|
|
pid_nav_lon (NAV_P, NAV_I, NAV_D, NAV_IMAX * 100),
|
2012-02-12 07:26:36 -04:00
|
|
|
|
2012-02-15 13:05:17 -04:00
|
|
|
pid_throttle (THROTTLE_P, THROTTLE_I, THROTTLE_D, THROTTLE_IMAX),
|
|
|
|
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),
|
2012-02-12 07:26:36 -04:00
|
|
|
|
|
|
|
// PI controller initial P initial I initial imax
|
2011-07-10 21:47:08 -03:00
|
|
|
//----------------------------------------------------------------------
|
2012-04-09 05:32:47 -03:00
|
|
|
pi_loiter_lat (LOITER_P, LOITER_I, LOITER_IMAX * 100),
|
|
|
|
pi_loiter_lon (LOITER_P, LOITER_I, LOITER_IMAX * 100),
|
|
|
|
|
2012-02-12 07:26:36 -04:00
|
|
|
pi_stabilize_roll (STABILIZE_ROLL_P, STABILIZE_ROLL_I, STABILIZE_ROLL_IMAX * 100),
|
|
|
|
pi_stabilize_pitch (STABILIZE_PITCH_P, STABILIZE_PITCH_I, STABILIZE_PITCH_IMAX * 100),
|
|
|
|
pi_stabilize_yaw (STABILIZE_YAW_P, STABILIZE_YAW_I, STABILIZE_YAW_IMAX * 100),
|
|
|
|
|
2012-04-09 05:32:47 -03:00
|
|
|
pi_alt_hold (ALT_HOLD_P, ALT_HOLD_I, ALT_HOLD_IMAX)
|
2011-07-10 21:47:08 -03:00
|
|
|
{
|
|
|
|
}
|
2011-02-17 03:09:13 -04:00
|
|
|
};
|
|
|
|
|
|
|
|
#endif // PARAMETERS_H
|
2011-08-01 02:12:10 -03:00
|
|
|
|