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.
//
2011-10-27 16:42:28 -03:00
static const uint16_t k_format_version = 112 ;
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
//
k_param_log_bitmask ,
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 ,
k_param_heli_servo1_pos ,
k_param_heli_servo2_pos ,
k_param_heli_servo3_pos ,
k_param_heli_roll_max ,
k_param_heli_pitch_max ,
k_param_heli_collective_min ,
k_param_heli_collective_max ,
k_param_heli_collective_mid ,
k_param_heli_ext_gyro_enabled ,
k_param_heli_ext_gyro_gain ,
2011-11-12 10:23:07 -04:00
k_param_heli_servo_averaging ,
2011-11-13 09:20:57 -04:00
k_param_heli_servo_manual ,
2011-11-16 04:19:29 -04:00
k_param_heli_phase_angle ,
2011-11-13 09:20:57 -04:00
k_param_heli_coll_yaw_effect , // 97
2011-09-25 04:51:25 -03:00
# endif
2011-09-25 16:24:02 -03:00
2011-07-10 21:47:08 -03:00
// 110: Telemetry control
//
k_param_streamrates_port0 = 110 ,
k_param_streamrates_port3 ,
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
//
k_param_IMU_calibration = 140 ,
k_param_battery_monitoring ,
k_param_pack_capacity ,
k_param_compass_enabled ,
k_param_compass ,
k_param_sonar ,
k_param_frame_orientation ,
k_param_top_bottom_ratio ,
2011-07-21 20:14:53 -03:00
k_param_optflow_enabled ,
2011-09-10 22:44:56 -03:00
k_param_input_voltage ,
2011-09-16 22:56:51 -03:00
k_param_low_voltage ,
2011-07-10 21:47:08 -03:00
//
// 160: Navigation parameters
//
k_param_crosstrack_entry_angle = 160 ,
k_param_RTL_altitude ,
//
// 180: Radio settings
//
k_param_rc_1 = 180 ,
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_9 ,
k_param_rc_10 ,
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 ,
2011-10-15 20:34:57 -03:00
k_param_camera_pitch_gain ,
k_param_camera_roll_gain ,
2011-07-12 17:04:15 -03:00
2011-07-17 07:30:53 -03:00
//
// 210: flight modes
//
k_param_flight_mode1 ,
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
//
// 220: Waypoint data
//
k_param_waypoint_mode = 220 ,
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 ,
//
2011-09-04 21:15:36 -03:00
// 240: PI/D Controllers
2011-07-10 21:47:08 -03:00
//
2011-10-27 15:52:00 -03:00
k_param_pi_rate_roll = 235 ,
2011-09-04 21:15:36 -03:00
k_param_pi_rate_pitch ,
k_param_pi_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_pi_nav_lat ,
k_param_pi_nav_lon ,
2011-10-02 15:36:23 -03:00
k_param_pi_alt_hold ,
2011-09-04 21:15:36 -03:00
k_param_pi_throttle ,
k_param_pi_crosstrack ,
2011-10-27 15:52:00 -03:00
k_param_pi_acro_roll ,
k_param_pi_acro_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
// Crosstrack navigation
//
AP_Int16 crosstrack_entry_angle ;
// 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 ;
// 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
// Radio settings
//
//AP_Var_group pwm_roll;
//AP_Var_group pwm_pitch;
//AP_Var_group pwm_throttle;
//AP_Var_group pwm_yaw;
// Misc
//
AP_Int16 log_bitmask ;
AP_Int16 RTL_altitude ;
AP_Int8 sonar_enabled ;
AP_Int8 battery_monitoring ; // 0=disabled, 1=3 cell lipo, 2=4 cell lipo, 3=total voltage only, 4=total voltage and current
2011-05-09 12:46:56 -03:00
AP_Int16 pack_capacity ; // Battery pack capacity less reserve
2011-07-10 21:47:08 -03:00
AP_Int8 compass_enabled ;
2011-05-06 19:46:57 -03:00
AP_Int8 esc_calibrate ;
2011-09-10 19:16:51 -03:00
AP_Int8 radio_tuning ;
2011-05-18 20:38:24 -03:00
AP_Int8 frame_orientation ;
2011-07-10 21:47:08 -03:00
AP_Float top_bottom_ratio ;
2011-07-21 20:14:53 -03:00
AP_Int8 optflow_enabled ;
2011-09-10 22:44:56 -03:00
AP_Float input_voltage ;
2011-09-16 22:56:51 -03:00
AP_Float low_voltage ;
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-11-13 09:20:57 -04:00
AP_Int16 heli_servo1_pos , heli_servo2_pos , heli_servo3_pos ; // servo positions (3 because we don't need pos for tail servo)
2011-07-10 21:47:08 -03:00
AP_Int16 heli_roll_max , heli_pitch_max ; // maximum allowed roll and pitch of swashplate
AP_Int16 heli_coll_min , heli_coll_max , heli_coll_mid ; // min and max collective. mid = main blades at zero pitch
AP_Int8 heli_ext_gyro_enabled ; // 0 = no external tail gyro, 1 = external tail gyro
2011-09-25 04:51:25 -03:00
AP_Int16 heli_ext_gyro_gain ; // radio output 1000~2000 (value output on CH_7)
AP_Int8 heli_servo_averaging ; // 0 or 1 = no averaging (250hz) for **digital servos**, 2=average of two samples (125hz), 3=three samples (83.3hz) **analog servos**, 4=four samples (62.5hz), 5=5 samples(50hz)
2011-11-12 10:23:07 -04:00
AP_Int8 heli_servo_manual ; // 0 = normal mode, 1 = radio inputs directly control swash. required for swash set-up
2011-11-13 09:20:57 -04:00
AP_Int16 heli_phase_angle ; // 0 to 360 degrees. specifies mixing between roll and pitch for helis
2011-11-16 04:19:29 -04:00
AP_Float heli_coll_yaw_effect ; // -5.0 ~ 5.0. Feed forward control from collective to yaw. 1.0 = move rudder right 1% for every 1% of collective above the mid point
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 ;
2011-10-15 20:34:57 -03:00
AP_Float camera_pitch_gain ;
AP_Float camera_roll_gain ;
2011-02-17 03:09:13 -04:00
2011-09-04 21:15:36 -03:00
// PI/D controllers
APM_PI pi_rate_roll ;
APM_PI pi_rate_pitch ;
APM_PI pi_rate_yaw ;
APM_PI pi_stabilize_roll ;
APM_PI pi_stabilize_pitch ;
APM_PI pi_stabilize_yaw ;
APM_PI pi_loiter_lat ;
APM_PI pi_loiter_lon ;
APM_PI pi_nav_lat ;
APM_PI pi_nav_lon ;
2011-10-02 15:36:23 -03:00
APM_PI pi_alt_hold ;
2011-09-04 21:15:36 -03:00
APM_PI pi_throttle ;
APM_PI pi_crosstrack ;
2011-07-10 21:47:08 -03:00
2011-10-27 15:52:00 -03:00
APM_PI pi_acro_roll ;
APM_PI pi_acro_pitch ;
2011-07-10 21:47:08 -03:00
uint8_t junk ;
// Note: keep initializers here in the same order as they are declared above.
Parameters ( ) :
// variable default key name
//-------------------------------------------------------------------------------------------------------------------
format_version ( k_format_version , k_param_format_version , PSTR ( " SYSID_SW_MREV " ) ) ,
software_type ( k_software_type , k_param_software_type , PSTR ( " SYSID_SW_TYPE " ) ) ,
sysid_this_mav ( MAV_SYSTEM_ID , k_param_sysid_this_mav , PSTR ( " SYSID_THISMAV " ) ) ,
sysid_my_gcs ( 255 , k_param_sysid_my_gcs , PSTR ( " SYSID_MYGCS " ) ) ,
2011-08-01 08:39:17 -03:00
serial3_baud ( SERIAL3_BAUD / 1000 , k_param_serial3_baud , PSTR ( " SERIAL3_BAUD " ) ) ,
2011-07-10 21:47:08 -03:00
//crosstrack_gain (XTRACK_GAIN * 100, k_param_crosstrack_gain, PSTR("XTRK_GAIN_SC")),
crosstrack_entry_angle ( XTRACK_ENTRY_ANGLE * 100 , k_param_crosstrack_entry_angle , PSTR ( " XTRK_ANGLE_CD " ) ) ,
sonar_enabled ( DISABLED , k_param_sonar , PSTR ( " SONAR_ENABLE " ) ) ,
battery_monitoring ( DISABLED , k_param_battery_monitoring , PSTR ( " BATT_MONITOR " ) ) ,
pack_capacity ( HIGH_DISCHARGE , k_param_pack_capacity , PSTR ( " BATT_CAPACITY " ) ) ,
compass_enabled ( MAGNETOMETER , k_param_compass_enabled , PSTR ( " MAG_ENABLE " ) ) ,
2011-07-21 20:14:53 -03:00
optflow_enabled ( OPTFLOW , k_param_optflow_enabled , PSTR ( " FLOW_ENABLE " ) ) ,
2011-09-10 22:44:56 -03:00
input_voltage ( INPUT_VOLTAGE , k_param_input_voltage , PSTR ( " IN_VOLT " ) ) ,
2011-09-16 22:56:51 -03:00
low_voltage ( LOW_VOLTAGE , k_param_low_voltage , PSTR ( " LOW_VOLT " ) ) ,
2011-07-10 21:47:08 -03:00
waypoint_mode ( 0 , k_param_waypoint_mode , PSTR ( " WP_MODE " ) ) ,
2011-11-05 01:41:51 -03:00
command_total ( 0 , k_param_command_total , PSTR ( " WP_TOTAL " ) ) ,
command_index ( 0 , k_param_command_index , PSTR ( " WP_INDEX " ) ) ,
2011-11-16 04:19:29 -04:00
command_nav_index ( 0 , k_param_command_nav_index , PSTR ( " WP_MUST_INDEX " ) ) ,
2011-07-10 21:47:08 -03:00
waypoint_radius ( WP_RADIUS_DEFAULT , k_param_waypoint_radius , PSTR ( " WP_RADIUS " ) ) ,
2011-11-13 04:24:25 -04:00
loiter_radius ( LOITER_RADIUS * 100 , k_param_loiter_radius , PSTR ( " WP_LOITER_RAD " ) ) ,
2011-07-10 21:47:08 -03:00
waypoint_speed_max ( WAYPOINT_SPEED_MAX , k_param_waypoint_speed_max , PSTR ( " WP_SPEED_MAX " ) ) ,
throttle_min ( 0 , k_param_throttle_min , PSTR ( " THR_MIN " ) ) ,
throttle_max ( 1000 , k_param_throttle_max , PSTR ( " THR_MAX " ) ) ,
throttle_fs_enabled ( THROTTLE_FAILSAFE , k_param_throttle_fs_enabled , PSTR ( " THR_FAILSAFE " ) ) ,
throttle_fs_action ( THROTTLE_FAILSAFE_ACTION , k_param_throttle_fs_action , PSTR ( " THR_FS_ACTION " ) ) ,
throttle_fs_value ( THROTTLE_FS_VALUE , k_param_throttle_fs_value , PSTR ( " THR_FS_VALUE " ) ) ,
2011-09-23 03:10:55 -03:00
throttle_cruise ( THROTTLE_CRUISE , k_param_throttle_cruise , PSTR ( " TRIM_THROTTLE " ) ) ,
2011-07-10 21:47:08 -03:00
2011-07-17 07:30:53 -03:00
flight_mode1 ( FLIGHT_MODE_1 , k_param_flight_mode1 , PSTR ( " FLTMODE1 " ) ) ,
flight_mode2 ( FLIGHT_MODE_2 , k_param_flight_mode2 , PSTR ( " FLTMODE2 " ) ) ,
flight_mode3 ( FLIGHT_MODE_3 , k_param_flight_mode3 , PSTR ( " FLTMODE3 " ) ) ,
flight_mode4 ( FLIGHT_MODE_4 , k_param_flight_mode4 , PSTR ( " FLTMODE4 " ) ) ,
flight_mode5 ( FLIGHT_MODE_5 , k_param_flight_mode5 , PSTR ( " FLTMODE5 " ) ) ,
flight_mode6 ( FLIGHT_MODE_6 , k_param_flight_mode6 , PSTR ( " FLTMODE6 " ) ) ,
2011-09-14 17:58:18 -03:00
simple_modes ( 0 , k_param_simple_modes , PSTR ( " SIMPLE " ) ) ,
2011-07-10 21:47:08 -03:00
2011-08-01 07:06:15 -03:00
log_bitmask ( DEFAULT_LOG_BITMASK , k_param_log_bitmask , PSTR ( " LOG_BITMASK " ) ) ,
2011-07-10 21:47:08 -03:00
RTL_altitude ( ALT_HOLD_HOME * 100 , k_param_RTL_altitude , PSTR ( " ALT_HOLD_RTL " ) ) ,
esc_calibrate ( 0 , k_param_esc_calibrate , PSTR ( " ESC " ) ) ,
2011-09-10 19:16:51 -03:00
radio_tuning ( 0 , k_param_radio_tuning , PSTR ( " TUNE " ) ) ,
2011-07-10 21:47:08 -03:00
frame_orientation ( FRAME_ORIENTATION , k_param_frame_orientation , PSTR ( " FRAME " ) ) ,
top_bottom_ratio ( TOP_BOTTOM_RATIO , k_param_top_bottom_ratio , PSTR ( " TB_RATIO " ) ) ,
# if FRAME_CONFIG == HELI_FRAME
heli_servo_1 ( k_param_heli_servo_1 , PSTR ( " HS1_ " ) ) ,
heli_servo_2 ( k_param_heli_servo_2 , PSTR ( " HS2_ " ) ) ,
heli_servo_3 ( k_param_heli_servo_3 , PSTR ( " HS3_ " ) ) ,
heli_servo_4 ( k_param_heli_servo_4 , PSTR ( " HS4_ " ) ) ,
heli_servo1_pos ( - 60 , k_param_heli_servo1_pos , PSTR ( " SV1_POS_ " ) ) ,
heli_servo2_pos ( 60 , k_param_heli_servo2_pos , PSTR ( " SV2_POS_ " ) ) ,
heli_servo3_pos ( 180 , k_param_heli_servo3_pos , PSTR ( " SV3_POS_ " ) ) ,
heli_roll_max ( 4500 , k_param_heli_roll_max , PSTR ( " ROL_MAX_ " ) ) ,
heli_pitch_max ( 4500 , k_param_heli_pitch_max , PSTR ( " PIT_MAX_ " ) ) ,
heli_coll_min ( 1000 , k_param_heli_collective_min , PSTR ( " COL_MIN_ " ) ) ,
heli_coll_max ( 2000 , k_param_heli_collective_max , PSTR ( " COL_MAX_ " ) ) ,
heli_coll_mid ( 1500 , k_param_heli_collective_mid , PSTR ( " COL_MID_ " ) ) ,
heli_ext_gyro_enabled ( 0 , k_param_heli_ext_gyro_enabled , PSTR ( " GYR_ENABLE_ " ) ) ,
heli_ext_gyro_gain ( 1000 , k_param_heli_ext_gyro_gain , PSTR ( " GYR_GAIN_ " ) ) ,
2011-09-25 04:51:25 -03:00
heli_servo_averaging ( 0 , k_param_heli_servo_averaging , PSTR ( " SV_AVG " ) ) ,
2011-11-12 10:23:07 -04:00
heli_servo_manual ( 0 , k_param_heli_servo_manual , PSTR ( " HSV_MAN " ) ) ,
2011-11-13 09:20:57 -04:00
heli_phase_angle ( 0 , k_param_heli_phase_angle , PSTR ( " H_PHANG " ) ) ,
heli_coll_yaw_effect ( 0 , k_param_heli_coll_yaw_effect , PSTR ( " H_COLYAW " ) ) ,
2011-07-10 21:47:08 -03:00
# endif
// RC channel group key name
//----------------------------------------------------------------------
rc_1 ( k_param_rc_1 , PSTR ( " RC1_ " ) ) ,
rc_2 ( k_param_rc_2 , PSTR ( " RC2_ " ) ) ,
rc_3 ( k_param_rc_3 , PSTR ( " RC3_ " ) ) ,
rc_4 ( k_param_rc_4 , PSTR ( " RC4_ " ) ) ,
rc_5 ( k_param_rc_5 , PSTR ( " RC5_ " ) ) ,
rc_6 ( k_param_rc_6 , PSTR ( " RC6_ " ) ) ,
rc_7 ( k_param_rc_7 , PSTR ( " RC7_ " ) ) ,
rc_8 ( k_param_rc_8 , PSTR ( " RC8_ " ) ) ,
2011-10-15 20:34:57 -03:00
rc_camera_pitch ( k_param_rc_9 , PSTR ( " CAM_P_ " ) ) ,
rc_camera_roll ( k_param_rc_10 , PSTR ( " CAM_R_ " ) ) ,
// variable default key name
//-------------------------------------------------------------------------------------------------------------------
2011-10-15 22:34:23 -03:00
camera_pitch_gain ( CAM_PITCH_GAIN , k_param_camera_pitch_gain , PSTR ( " CAM_P_G " ) ) ,
2011-10-15 20:34:57 -03:00
camera_roll_gain ( CAM_ROLL_GAIN , k_param_camera_roll_gain , PSTR ( " CAM_R_G " ) ) ,
2011-07-12 17:04:15 -03:00
2011-09-04 21:15:36 -03:00
// PI controller group key name initial P initial I initial imax
2011-07-10 21:47:08 -03:00
//--------------------------------------------------------------------------------------------------------------------------------------------------------------------
2011-09-04 21:15:36 -03:00
pi_rate_roll ( k_param_pi_rate_roll , PSTR ( " RATE_RLL_ " ) , RATE_ROLL_P , RATE_ROLL_I , RATE_ROLL_IMAX * 100 ) ,
pi_rate_pitch ( k_param_pi_rate_pitch , PSTR ( " RATE_PIT_ " ) , RATE_PITCH_P , RATE_PITCH_I , RATE_PITCH_IMAX * 100 ) ,
pi_rate_yaw ( k_param_pi_rate_yaw , PSTR ( " RATE_YAW_ " ) , RATE_YAW_P , RATE_YAW_I , RATE_YAW_IMAX * 100 ) ,
2011-07-10 21:47:08 -03:00
2011-09-04 21:15:36 -03:00
pi_stabilize_roll ( k_param_pi_stabilize_roll , PSTR ( " STB_RLL_ " ) , STABILIZE_ROLL_P , STABILIZE_ROLL_I , STABILIZE_ROLL_IMAX * 100 ) ,
pi_stabilize_pitch ( k_param_pi_stabilize_pitch , PSTR ( " STB_PIT_ " ) , STABILIZE_PITCH_P , STABILIZE_PITCH_I , STABILIZE_PITCH_IMAX * 100 ) ,
pi_stabilize_yaw ( k_param_pi_stabilize_yaw , PSTR ( " STB_YAW_ " ) , STABILIZE_YAW_P , STABILIZE_YAW_I , STABILIZE_YAW_IMAX * 100 ) ,
2011-07-10 21:47:08 -03:00
2011-09-05 13:00:49 -03:00
pi_loiter_lat ( k_param_pi_loiter_lat , PSTR ( " HLD_LAT_ " ) , LOITER_P , LOITER_I , LOITER_IMAX * 100 ) ,
pi_loiter_lon ( k_param_pi_loiter_lon , PSTR ( " HLD_LON_ " ) , LOITER_P , LOITER_I , LOITER_IMAX * 100 ) ,
2011-07-10 21:47:08 -03:00
2011-09-04 21:15:36 -03:00
pi_nav_lat ( k_param_pi_nav_lat , PSTR ( " NAV_LAT_ " ) , NAV_P , NAV_I , NAV_IMAX * 100 ) ,
pi_nav_lon ( k_param_pi_nav_lon , PSTR ( " NAV_LON_ " ) , NAV_P , NAV_I , NAV_IMAX * 100 ) ,
2011-07-10 21:47:08 -03:00
2011-10-02 15:36:23 -03:00
pi_alt_hold ( k_param_pi_alt_hold , PSTR ( " THR_ALT_ " ) , THR_HOLD_P , THR_HOLD_I , THR_HOLD_IMAX ) ,
pi_throttle ( k_param_pi_throttle , PSTR ( " THR_RATE_ " ) , THROTTLE_P , THROTTLE_I , THROTTLE_IMAX ) ,
2011-09-04 21:15:36 -03:00
pi_crosstrack ( k_param_pi_crosstrack , PSTR ( " XTRACK_ " ) , XTRACK_P , XTRACK_I , XTRACK_IMAX ) ,
2011-07-10 21:47:08 -03:00
2011-10-27 15:52:00 -03:00
pi_acro_roll ( k_param_pi_acro_roll , PSTR ( " ACRO_RLL_ " ) , ACRO_ROLL_P , ACRO_ROLL_I , ACRO_ROLL_IMAX * 100 ) ,
pi_acro_pitch ( k_param_pi_acro_pitch , PSTR ( " ACRO_PIT_ " ) , ACRO_PITCH_P , ACRO_PITCH_I , ACRO_PITCH_IMAX * 100 ) ,
2011-07-10 21:47:08 -03:00
junk ( 0 ) // XXX just so that we can add things without worrying about the trailing comma
{
}
2011-02-17 03:09:13 -04:00
} ;
# endif // PARAMETERS_H
2011-08-01 02:12:10 -03:00