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:
|
2012-08-16 21:50:03 -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-10-19 04:14:51 -03:00
|
|
|
static const uint16_t k_format_version = 120;
|
2012-07-14 23:26:17 -03:00
|
|
|
|
2012-08-16 21:50:03 -03:00
|
|
|
// The parameter software_type is set up solely for ground station use
|
|
|
|
// 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.
|
2012-07-14 23:26:17 -03:00
|
|
|
//
|
2012-08-16 21:50:03 -03:00
|
|
|
static const uint16_t k_software_type = 10; // 0 for APM
|
|
|
|
// trunk
|
2011-07-12 17:04:15 -03:00
|
|
|
|
2012-08-16 21:50:03 -03:00
|
|
|
// 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
|
2012-12-03 17:26:36 -04:00
|
|
|
// AP_Param to store and locate parameters in EEPROM.
|
2012-08-16 21:50:03 -03:00
|
|
|
//
|
|
|
|
// 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
|
2012-12-03 17:26:36 -04:00
|
|
|
// AP_Param load/save code depends on the values here to identify
|
2012-08-16 21:50:03 -03:00
|
|
|
// variables saved in EEPROM.
|
2011-07-17 07:30:53 -03:00
|
|
|
//
|
|
|
|
//
|
2012-08-16 21:50:03 -03:00
|
|
|
enum {
|
|
|
|
// Layout version number, always key zero.
|
|
|
|
//
|
|
|
|
k_param_format_version = 0,
|
|
|
|
k_param_software_type,
|
2012-11-07 02:20:22 -04:00
|
|
|
k_param_ins_old, // *** Deprecated, remove with next eeprom number change
|
|
|
|
k_param_ins, // libraries/AP_InertialSensor variables
|
2012-08-16 21:50:03 -03:00
|
|
|
|
|
|
|
// simulation
|
|
|
|
k_param_sitl = 10,
|
|
|
|
|
2012-12-18 06:15:11 -04:00
|
|
|
// barometer object (needed for SITL)
|
|
|
|
k_param_barometer,
|
|
|
|
|
2013-01-11 21:01:10 -04:00
|
|
|
// scheduler object (for debugging)
|
|
|
|
k_param_scheduler,
|
|
|
|
|
2012-08-16 21:50:03 -03:00
|
|
|
// 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
|
|
|
|
|
2013-03-17 04:46:31 -03:00
|
|
|
k_param_crosstrack_min_distance, // deprecated - remove with next eeprom number change
|
2012-11-22 05:59:33 -04:00
|
|
|
k_param_rssi_pin,
|
2012-12-03 10:05:14 -04:00
|
|
|
k_param_throttle_accel_enabled,
|
2013-04-18 03:30:18 -03:00
|
|
|
k_param_wp_yaw_behavior,
|
2012-12-21 23:52:49 -04:00
|
|
|
k_param_acro_trainer_enabled,
|
2013-04-20 00:03:55 -03:00
|
|
|
k_param_pilot_velocity_z_max,
|
2013-04-20 03:58:36 -03:00
|
|
|
k_param_circle_rate,
|
2013-05-17 02:42:28 -03:00
|
|
|
k_param_sonar_gain,
|
2013-05-20 02:48:04 -03:00
|
|
|
k_param_ch8_option,
|
|
|
|
k_param_arming_check_enabled, // 32
|
2012-11-10 01:55:51 -04:00
|
|
|
|
2012-08-16 21:50:03 -03:00
|
|
|
// 65: AP_Limits Library
|
2013-04-26 10:57:05 -03:00
|
|
|
k_param_limits = 65, // deprecated - remove
|
|
|
|
k_param_gpslock_limit, // deprecated - remove
|
|
|
|
k_param_geofence_limit, // deprecated - remove
|
|
|
|
k_param_altitude_limit, // deprecated - remove
|
|
|
|
k_param_fence, // 69
|
2012-08-16 21:50:03 -03:00
|
|
|
|
|
|
|
//
|
|
|
|
// 80: Heli
|
|
|
|
//
|
|
|
|
k_param_heli_servo_1 = 80,
|
|
|
|
k_param_heli_servo_2,
|
|
|
|
k_param_heli_servo_3,
|
|
|
|
k_param_heli_servo_4,
|
2012-12-04 14:47:38 -04:00
|
|
|
k_param_heli_pitch_ff,
|
|
|
|
k_param_heli_roll_ff,
|
|
|
|
k_param_heli_yaw_ff,
|
2012-08-16 21:50:03 -03:00
|
|
|
|
|
|
|
//
|
|
|
|
// 90: Motors
|
|
|
|
//
|
|
|
|
k_param_motors = 90,
|
|
|
|
|
2012-11-07 06:03:30 -04:00
|
|
|
//
|
|
|
|
// 100: Inertial Nav
|
|
|
|
//
|
|
|
|
k_param_inertial_nav = 100,
|
2013-04-05 06:32:36 -03:00
|
|
|
k_param_wp_nav = 101,
|
2012-11-07 06:03:30 -04:00
|
|
|
|
2012-08-16 21:50:03 -03:00
|
|
|
// 110: Telemetry control
|
|
|
|
//
|
|
|
|
k_param_gcs0 = 110,
|
|
|
|
k_param_gcs3,
|
|
|
|
k_param_sysid_this_mav,
|
|
|
|
k_param_sysid_my_gcs,
|
|
|
|
k_param_serial3_baud,
|
2012-08-29 20:03:01 -03:00
|
|
|
k_param_telem_delay,
|
2012-08-16 21:50:03 -03:00
|
|
|
|
|
|
|
//
|
|
|
|
// 140: Sensor parameters
|
|
|
|
//
|
2012-11-05 00:32:38 -04:00
|
|
|
k_param_imu = 140, // deprecated - can be deleted
|
|
|
|
k_param_battery_monitoring = 141,
|
2012-08-16 21:50:03 -03:00
|
|
|
k_param_volt_div_ratio,
|
|
|
|
k_param_curr_amp_per_volt,
|
2013-03-03 10:23:54 -04:00
|
|
|
k_param_input_voltage, // deprecated - can be deleted
|
2012-08-16 21:50:03 -03:00
|
|
|
k_param_pack_capacity,
|
|
|
|
k_param_compass_enabled,
|
|
|
|
k_param_compass,
|
|
|
|
k_param_sonar_enabled,
|
|
|
|
k_param_frame_orientation,
|
|
|
|
k_param_optflow_enabled,
|
|
|
|
k_param_low_voltage,
|
|
|
|
k_param_ch7_option,
|
2013-05-17 04:09:17 -03:00
|
|
|
k_param_auto_slew_rate, // deprecated - can be deleted
|
2012-08-16 21:50:03 -03:00
|
|
|
k_param_sonar_type,
|
2012-10-13 06:40:46 -03:00
|
|
|
k_param_super_simple = 155,
|
|
|
|
k_param_axis_enabled = 157,
|
2012-08-16 21:50:03 -03:00
|
|
|
k_param_copter_leds_mode,
|
|
|
|
k_param_ahrs, // AHRS group
|
|
|
|
|
|
|
|
//
|
|
|
|
// 160: Navigation parameters
|
|
|
|
//
|
2012-11-29 08:08:19 -04:00
|
|
|
k_param_rtl_altitude = 160,
|
2013-03-17 04:46:31 -03:00
|
|
|
k_param_crosstrack_gain, // deprecated - remove with next eeprom number change
|
2012-11-29 08:08:19 -04:00
|
|
|
k_param_rtl_loiter_time,
|
|
|
|
k_param_rtl_alt_final,
|
2013-03-17 04:53:32 -03:00
|
|
|
k_param_tilt_comp, //164 deprecated - remove with next eeprom number change
|
2012-08-16 21:50:03 -03:00
|
|
|
|
|
|
|
|
|
|
|
//
|
|
|
|
// Camera and mount parameters
|
|
|
|
//
|
|
|
|
k_param_camera = 165,
|
|
|
|
k_param_camera_mount,
|
|
|
|
k_param_camera_mount2,
|
|
|
|
|
2012-10-13 06:40:46 -03:00
|
|
|
//
|
|
|
|
// Batery monitoring parameters
|
|
|
|
//
|
|
|
|
k_param_battery_volt_pin = 168,
|
|
|
|
k_param_battery_curr_pin, // 169
|
|
|
|
|
2012-08-16 21:50:03 -03:00
|
|
|
//
|
|
|
|
// 170: Radio settings
|
|
|
|
//
|
|
|
|
k_param_rc_1 = 170,
|
|
|
|
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,
|
|
|
|
k_param_rc_10,
|
2012-09-02 00:51:23 -03:00
|
|
|
k_param_rc_11,
|
2012-08-16 21:50:03 -03:00
|
|
|
k_param_throttle_min,
|
|
|
|
k_param_throttle_max,
|
2012-12-10 10:38:43 -04:00
|
|
|
k_param_failsafe_throttle,
|
|
|
|
k_param_throttle_fs_action, // remove
|
|
|
|
k_param_failsafe_throttle_value,
|
2012-08-16 21:50:03 -03:00
|
|
|
k_param_throttle_cruise,
|
|
|
|
k_param_esc_calibrate,
|
|
|
|
k_param_radio_tuning,
|
|
|
|
k_param_radio_tuning_high,
|
|
|
|
k_param_radio_tuning_low,
|
|
|
|
k_param_rc_speed = 192,
|
2013-01-30 11:25:41 -04:00
|
|
|
k_param_failsafe_battery_enabled,
|
2013-03-16 05:27:46 -03:00
|
|
|
k_param_throttle_mid,
|
2013-04-29 09:30:22 -03:00
|
|
|
k_param_failsafe_gps_enabled,
|
2013-04-25 07:01:34 -03:00
|
|
|
k_param_rc_9,
|
|
|
|
k_param_rc_12,
|
2013-04-29 09:30:22 -03:00
|
|
|
k_param_failsafe_gcs, // 198
|
2012-08-16 21:50:03 -03:00
|
|
|
|
|
|
|
//
|
|
|
|
// 200: flight modes
|
|
|
|
//
|
|
|
|
k_param_flight_mode1 = 200,
|
|
|
|
k_param_flight_mode2,
|
|
|
|
k_param_flight_mode3,
|
|
|
|
k_param_flight_mode4,
|
|
|
|
k_param_flight_mode5,
|
|
|
|
k_param_flight_mode6,
|
|
|
|
k_param_simple_modes,
|
|
|
|
|
|
|
|
//
|
|
|
|
// 210: Waypoint data
|
|
|
|
//
|
|
|
|
k_param_waypoint_mode = 210, // remove
|
|
|
|
k_param_command_total,
|
|
|
|
k_param_command_index,
|
2012-12-10 08:45:57 -04:00
|
|
|
k_param_command_nav_index, // remove
|
2013-04-14 01:27:37 -03:00
|
|
|
k_param_waypoint_radius, // remove
|
2012-12-10 08:45:57 -04:00
|
|
|
k_param_circle_radius,
|
2013-04-14 01:27:37 -03:00
|
|
|
k_param_waypoint_speed_max, // remove
|
2012-12-21 23:52:49 -04:00
|
|
|
k_param_land_speed,
|
2013-04-18 02:52:21 -03:00
|
|
|
k_param_auto_velocity_z_min, // remove
|
|
|
|
k_param_auto_velocity_z_max, // remove - 219
|
2012-08-16 21:50:03 -03:00
|
|
|
|
|
|
|
//
|
|
|
|
// 220: PI/D Controllers
|
|
|
|
//
|
2012-11-10 01:55:51 -04:00
|
|
|
k_param_acro_p = 221,
|
2012-12-10 08:45:57 -04:00
|
|
|
k_param_axis_lock_p, // remove
|
2012-08-16 21:50:03 -03:00
|
|
|
k_param_pid_rate_roll,
|
|
|
|
k_param_pid_rate_pitch,
|
|
|
|
k_param_pid_rate_yaw,
|
|
|
|
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,
|
|
|
|
k_param_pid_loiter_rate_lat,
|
|
|
|
k_param_pid_loiter_rate_lon,
|
2013-04-14 00:12:51 -03:00
|
|
|
k_param_pid_nav_lat, // 233 - remove
|
|
|
|
k_param_pid_nav_lon, // 234 - remove
|
2012-08-16 21:50:03 -03:00
|
|
|
k_param_pi_alt_hold,
|
|
|
|
k_param_pid_throttle,
|
|
|
|
k_param_pid_optflow_roll,
|
|
|
|
k_param_pid_optflow_pitch,
|
2012-12-10 09:27:46 -04:00
|
|
|
k_param_acro_balance_roll, // scalar (not PID)
|
|
|
|
k_param_acro_balance_pitch, // scalar (not PID)
|
2012-11-23 02:57:49 -04:00
|
|
|
k_param_pid_throttle_accel, // 241
|
2012-08-16 21:50:03 -03:00
|
|
|
|
|
|
|
// 254,255: reserved
|
|
|
|
};
|
|
|
|
|
|
|
|
AP_Int16 format_version;
|
|
|
|
AP_Int8 software_type;
|
|
|
|
|
|
|
|
// Telemetry control
|
|
|
|
//
|
|
|
|
AP_Int16 sysid_this_mav;
|
|
|
|
AP_Int16 sysid_my_gcs;
|
|
|
|
AP_Int8 serial3_baud;
|
2012-08-29 20:03:01 -03:00
|
|
|
AP_Int8 telem_delay;
|
2012-08-16 21:50:03 -03:00
|
|
|
|
2012-11-29 08:08:19 -04:00
|
|
|
AP_Int16 rtl_altitude;
|
2012-08-16 21:50:03 -03:00
|
|
|
AP_Int8 sonar_enabled;
|
|
|
|
AP_Int8 sonar_type; // 0 = XL, 1 = LV,
|
|
|
|
// 2 = XLL (XL with 10m range)
|
|
|
|
// 3 = HRLV
|
2013-04-20 03:58:36 -03:00
|
|
|
AP_Float sonar_gain;
|
2012-08-16 21:50:03 -03: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;
|
2012-11-13 10:43:54 -04:00
|
|
|
AP_Int16 pack_capacity; // Battery pack capacity less reserve
|
2012-12-10 10:47:14 -04:00
|
|
|
AP_Int8 failsafe_battery_enabled; // battery failsafe enabled
|
2013-03-16 05:27:46 -03:00
|
|
|
AP_Int8 failsafe_gps_enabled; // gps failsafe enabled
|
2013-04-29 09:30:22 -03:00
|
|
|
AP_Int8 failsafe_gcs; // ground station failsafe behavior
|
2012-11-13 10:43:54 -04:00
|
|
|
|
2012-08-16 21:50:03 -03:00
|
|
|
AP_Int8 compass_enabled;
|
|
|
|
AP_Int8 optflow_enabled;
|
|
|
|
AP_Float low_voltage;
|
|
|
|
AP_Int8 super_simple;
|
2012-11-29 08:08:19 -04:00
|
|
|
AP_Int16 rtl_alt_final;
|
2012-08-16 21:50:03 -03:00
|
|
|
AP_Int8 axis_enabled;
|
|
|
|
AP_Int8 copter_leds_mode; // Operating mode of LED
|
|
|
|
// lighting system
|
|
|
|
|
2012-10-13 06:40:46 -03:00
|
|
|
AP_Int8 battery_volt_pin;
|
|
|
|
AP_Int8 battery_curr_pin;
|
2012-11-22 05:59:33 -04:00
|
|
|
AP_Int8 rssi_pin;
|
2012-12-03 10:05:14 -04:00
|
|
|
AP_Int8 throttle_accel_enabled; // enable/disable accel based throttle controller
|
2013-04-18 03:30:18 -03:00
|
|
|
AP_Int8 wp_yaw_behavior; // controls how the autopilot controls yaw during missions
|
2012-08-16 21:50:03 -03:00
|
|
|
|
|
|
|
// Waypoints
|
|
|
|
//
|
|
|
|
AP_Int8 command_total;
|
|
|
|
AP_Int8 command_index;
|
2012-12-10 08:45:57 -04:00
|
|
|
AP_Int16 circle_radius;
|
2013-04-20 00:03:55 -03:00
|
|
|
AP_Float circle_rate; // Circle mode's turn rate in deg/s. positive to rotate clockwise, negative for counter clockwise
|
2012-11-29 08:08:19 -04:00
|
|
|
AP_Int32 rtl_loiter_time;
|
2012-11-24 09:50:09 -04:00
|
|
|
AP_Int16 land_speed;
|
2012-12-21 23:52:49 -04:00
|
|
|
AP_Int16 pilot_velocity_z_max; // maximum vertical velocity the pilot may request
|
2012-08-16 21:50:03 -03:00
|
|
|
|
|
|
|
|
|
|
|
// Throttle
|
|
|
|
//
|
|
|
|
AP_Int16 throttle_min;
|
|
|
|
AP_Int16 throttle_max;
|
2012-12-10 10:38:43 -04:00
|
|
|
AP_Int8 failsafe_throttle;
|
|
|
|
AP_Int16 failsafe_throttle_value;
|
2012-08-16 21:50:03 -03:00
|
|
|
AP_Int16 throttle_cruise;
|
2013-01-30 11:25:41 -04:00
|
|
|
AP_Int16 throttle_mid;
|
2012-08-16 21:50:03 -03:00
|
|
|
|
|
|
|
// Flight modes
|
|
|
|
//
|
|
|
|
AP_Int8 flight_mode1;
|
|
|
|
AP_Int8 flight_mode2;
|
|
|
|
AP_Int8 flight_mode3;
|
|
|
|
AP_Int8 flight_mode4;
|
|
|
|
AP_Int8 flight_mode5;
|
|
|
|
AP_Int8 flight_mode6;
|
|
|
|
AP_Int8 simple_modes;
|
|
|
|
|
|
|
|
// Misc
|
|
|
|
//
|
|
|
|
AP_Int16 log_bitmask;
|
2012-12-10 08:45:57 -04:00
|
|
|
|
2012-08-16 21:50:03 -03:00
|
|
|
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;
|
|
|
|
AP_Int16 radio_tuning_low;
|
|
|
|
AP_Int8 frame_orientation;
|
|
|
|
AP_Int8 ch7_option;
|
2013-05-17 02:42:28 -03:00
|
|
|
AP_Int8 ch8_option;
|
2013-05-20 02:48:04 -03:00
|
|
|
AP_Int8 arming_check_enabled;
|
2012-08-16 21:50:03 -03:00
|
|
|
|
|
|
|
#if FRAME_CONFIG == HELI_FRAME
|
|
|
|
// Heli
|
2013-05-21 03:33:41 -03:00
|
|
|
RC_Channel heli_servo_1, heli_servo_2, heli_servo_3, heli_servo_4; // servos for swash plate and tail
|
|
|
|
AP_Float heli_pitch_ff; // pitch rate feed-forward
|
|
|
|
AP_Float heli_roll_ff; // roll rate feed-forward
|
|
|
|
AP_Float heli_yaw_ff; // yaw rate feed-forward
|
2012-08-16 21:50:03 -03:00
|
|
|
#endif
|
|
|
|
|
|
|
|
// RC channels
|
|
|
|
RC_Channel rc_1;
|
|
|
|
RC_Channel rc_2;
|
|
|
|
RC_Channel rc_3;
|
|
|
|
RC_Channel rc_4;
|
2012-09-02 00:51:23 -03:00
|
|
|
RC_Channel_aux rc_5;
|
|
|
|
RC_Channel_aux rc_6;
|
|
|
|
RC_Channel_aux rc_7;
|
|
|
|
RC_Channel_aux rc_8;
|
2012-07-15 04:36:05 -03:00
|
|
|
|
|
|
|
#if MOUNT == ENABLED
|
2012-08-16 21:50:03 -03:00
|
|
|
RC_Channel_aux rc_10;
|
|
|
|
RC_Channel_aux rc_11;
|
2012-07-15 04:36:05 -03:00
|
|
|
#endif
|
2013-04-25 07:01:34 -03:00
|
|
|
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
|
|
|
RC_Channel_aux rc_9;
|
|
|
|
RC_Channel_aux rc_12;
|
|
|
|
#endif
|
|
|
|
|
2012-08-16 21:50:03 -03:00
|
|
|
AP_Int16 rc_speed; // speed of fast RC Channels in Hz
|
|
|
|
|
2012-10-23 09:30:50 -03:00
|
|
|
// Acro parameters
|
2012-08-16 21:50:03 -03:00
|
|
|
AP_Float acro_p;
|
2012-10-23 09:30:50 -03:00
|
|
|
AP_Int16 acro_balance_roll;
|
|
|
|
AP_Int16 acro_balance_pitch;
|
2012-12-10 09:27:46 -04:00
|
|
|
AP_Int8 acro_trainer_enabled;
|
2012-08-16 21:50:03 -03:00
|
|
|
|
2012-10-23 09:30:50 -03:00
|
|
|
// PI/D controllers
|
2012-08-16 21:50:03 -03:00
|
|
|
AC_PID pid_rate_roll;
|
|
|
|
AC_PID pid_rate_pitch;
|
|
|
|
AC_PID pid_rate_yaw;
|
|
|
|
AC_PID pid_loiter_rate_lat;
|
|
|
|
AC_PID pid_loiter_rate_lon;
|
|
|
|
|
|
|
|
AC_PID pid_throttle;
|
2012-11-23 02:57:49 -04:00
|
|
|
AC_PID pid_throttle_accel;
|
2012-08-16 21:50:03 -03:00
|
|
|
AC_PID pid_optflow_roll;
|
|
|
|
AC_PID pid_optflow_pitch;
|
|
|
|
|
|
|
|
APM_PI pi_loiter_lat;
|
|
|
|
APM_PI pi_loiter_lon;
|
|
|
|
APM_PI pi_stabilize_roll;
|
|
|
|
APM_PI pi_stabilize_pitch;
|
|
|
|
APM_PI pi_stabilize_yaw;
|
|
|
|
APM_PI pi_alt_hold;
|
|
|
|
|
|
|
|
// Note: keep initializers here in the same order as they are declared
|
|
|
|
// above.
|
|
|
|
Parameters() :
|
|
|
|
|
|
|
|
#if FRAME_CONFIG == HELI_FRAME
|
2012-09-11 00:22:11 -03:00
|
|
|
heli_servo_1 (CH_1),
|
|
|
|
heli_servo_2 (CH_2),
|
|
|
|
heli_servo_3 (CH_3),
|
|
|
|
heli_servo_4 (CH_4),
|
2012-08-06 18:30:02 -03:00
|
|
|
#endif
|
|
|
|
|
2012-09-11 00:22:11 -03:00
|
|
|
rc_1 (CH_1),
|
|
|
|
rc_2 (CH_2),
|
|
|
|
rc_3 (CH_3),
|
|
|
|
rc_4 (CH_4),
|
|
|
|
rc_5 (CH_5),
|
|
|
|
rc_6 (CH_6),
|
|
|
|
rc_7 (CH_7),
|
|
|
|
rc_8 (CH_8),
|
2013-04-25 07:01:34 -03:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
|
|
|
rc_9 (CH_9),
|
|
|
|
rc_10 (CH_10),
|
|
|
|
rc_11 (CH_11),
|
|
|
|
rc_12 (CH_12),
|
|
|
|
#elif MOUNT == ENABLED
|
2012-09-11 00:22:11 -03:00
|
|
|
rc_10 (CH_10),
|
|
|
|
rc_11 (CH_11),
|
2012-08-05 18:08:31 -03:00
|
|
|
#endif
|
|
|
|
|
2012-08-16 21:50:03 -03:00
|
|
|
// PID controller initial P initial I initial D
|
|
|
|
// initial imax
|
|
|
|
//-----------------------------------------------------------------------------------------------------
|
2012-09-11 00:22:11 -03:00
|
|
|
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),
|
2012-02-15 13:05:17 -04:00
|
|
|
|
2012-08-16 21:50:03 -03:00
|
|
|
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-09-11 00:22:11 -03:00
|
|
|
pid_throttle (THROTTLE_P, THROTTLE_I, THROTTLE_D, THROTTLE_IMAX),
|
2012-11-23 02:57:49 -04:00
|
|
|
pid_throttle_accel (THROTTLE_ACCEL_P, THROTTLE_ACCEL_I, THROTTLE_ACCEL_D, THROTTLE_ACCEL_IMAX),
|
2012-08-16 21:50:03 -03:00
|
|
|
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
|
|
|
|
2012-08-16 21:50:03 -03:00
|
|
|
// PI controller initial P initial I initial
|
|
|
|
// imax
|
|
|
|
//----------------------------------------------------------------------
|
2012-09-11 00:22:11 -03:00
|
|
|
pi_loiter_lat (LOITER_P, LOITER_I, LOITER_IMAX * 100),
|
|
|
|
pi_loiter_lon (LOITER_P, LOITER_I, LOITER_IMAX * 100),
|
2012-04-09 05:32:47 -03:00
|
|
|
|
2012-08-16 21:50:03 -03: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-02-12 07:26:36 -04:00
|
|
|
|
2012-09-11 00:22:11 -03:00
|
|
|
pi_alt_hold (ALT_HOLD_P, ALT_HOLD_I, ALT_HOLD_IMAX)
|
2012-08-16 21:50:03 -03:00
|
|
|
{
|
|
|
|
}
|
2011-02-17 03:09:13 -04:00
|
|
|
};
|
|
|
|
|
2012-08-16 21:50:03 -03:00
|
|
|
extern const AP_Param::Info var_info[];
|
2012-08-06 22:03:26 -03:00
|
|
|
|
2011-02-17 03:09:13 -04:00
|
|
|
#endif // PARAMETERS_H
|
2011-08-01 02:12:10 -03:00
|
|
|
|