mirror of https://github.com/ArduPilot/ardupilot
cleanup
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1692 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
a329aa18fe
commit
934df2e9f3
|
@ -149,7 +149,7 @@ public:
|
||||||
AP_Int8 throttle_failsafe_enabled;
|
AP_Int8 throttle_failsafe_enabled;
|
||||||
AP_Int8 throttle_failsafe_action;
|
AP_Int8 throttle_failsafe_action;
|
||||||
AP_Int16 throttle_failsafe_value;
|
AP_Int16 throttle_failsafe_value;
|
||||||
AP_Int8 throttle_cruise;
|
AP_Int16 throttle_cruise;
|
||||||
|
|
||||||
// Flight modes
|
// Flight modes
|
||||||
//
|
//
|
||||||
|
@ -208,25 +208,25 @@ public:
|
||||||
uint8_t junk;
|
uint8_t junk;
|
||||||
|
|
||||||
Parameters() :
|
Parameters() :
|
||||||
// variable default key name
|
// variable default key name
|
||||||
//-------------------------------------------------------------------------------------------------------
|
//-------------------------------------------------------------------------------------------------------------------
|
||||||
format_version (k_format_version, k_param_format_version, NULL),
|
format_version (k_format_version, k_param_format_version, NULL),
|
||||||
|
|
||||||
crosstrack_gain (XTRACK_GAIN_SCALED, k_param_crosstrack_gain, PSTR("XTRK_GAIN_SCALED")),
|
crosstrack_gain (XTRACK_GAIN * 100, k_param_crosstrack_gain, PSTR("XTRK_GAIN")),
|
||||||
crosstrack_entry_angle (XTRACK_ENTRY_ANGLE_CENTIDEGREE,k_param_crosstrack_entry_angle, PSTR("XTRACK_ENTRY_ANGLE_CENTIDEGREE")),
|
crosstrack_entry_angle (XTRACK_ENTRY_ANGLE * 100, k_param_crosstrack_entry_angle, PSTR("XTRACK_ANGLE")),
|
||||||
|
|
||||||
frame_type (FRAME_CONFIG, k_param_frame_type, PSTR("FRAME_CONFIG")),
|
frame_type (FRAME_CONFIG, k_param_frame_type, PSTR("FRAME_CONFIG")),
|
||||||
|
|
||||||
current_enabled (DISABLED, k_param_current, PSTR("CURRENT_ENABLE")),
|
current_enabled (DISABLED, k_param_current, PSTR("CURRENT_ENABLE")),
|
||||||
milliamp_hours (2100, k_param_milliamp_hours, PSTR("MAH")),
|
milliamp_hours (2100, k_param_milliamp_hours, PSTR("MAH")),
|
||||||
compass_enabled (DISABLED, k_param_compass, PSTR("COMPASS_ENABLE")),
|
compass_enabled (DISABLED, k_param_compass, PSTR("COMPASS_ENABLE")),
|
||||||
|
|
||||||
waypoint_mode (0, k_param_waypoint_mode, PSTR("WP_MODE")),
|
waypoint_mode (0, k_param_waypoint_mode, PSTR("WP_MODE")),
|
||||||
waypoint_total (0, k_param_waypoint_total, PSTR("WP_TOTAL")),
|
waypoint_total (0, k_param_waypoint_total, PSTR("WP_TOTAL")),
|
||||||
waypoint_index (0, k_param_waypoint_index, PSTR("WP_INDEX")),
|
waypoint_index (0, k_param_waypoint_index, PSTR("WP_INDEX")),
|
||||||
command_must_index (0, k_param_command_must_index, PSTR("WP_MUST_INDEX")),
|
command_must_index (0, k_param_command_must_index, PSTR("WP_MUST_INDEX")),
|
||||||
waypoint_radius (WP_RADIUS_DEFAULT, k_param_waypoint_radius, PSTR("WP_RADIUS")),
|
waypoint_radius (WP_RADIUS_DEFAULT, k_param_waypoint_radius, PSTR("WP_RADIUS")),
|
||||||
loiter_radius (LOITER_RADIUS_DEFAULT, k_param_loiter_radius, PSTR("LOITER_RADIUS")),
|
loiter_radius (LOITER_RADIUS_DEFAULT, k_param_loiter_radius, PSTR("LOITER_RADIUS")),
|
||||||
|
|
||||||
throttle_min (THROTTLE_MIN, k_param_throttle_min, PSTR("THR_MIN")),
|
throttle_min (THROTTLE_MIN, k_param_throttle_min, PSTR("THR_MIN")),
|
||||||
throttle_max (THROTTLE_MAX, k_param_throttle_max, PSTR("THR_MAX")),
|
throttle_max (THROTTLE_MAX, k_param_throttle_max, PSTR("THR_MAX")),
|
||||||
|
@ -235,15 +235,15 @@ public:
|
||||||
throttle_failsafe_value (THROTTLE_FS_VALUE, k_param_throttle_failsafe_value, PSTR("THR_FS_VALUE")),
|
throttle_failsafe_value (THROTTLE_FS_VALUE, k_param_throttle_failsafe_value, PSTR("THR_FS_VALUE")),
|
||||||
throttle_cruise (THROTTLE_CRUISE, k_param_throttle_cruise, PSTR("TRIM_THROTTLE")),
|
throttle_cruise (THROTTLE_CRUISE, k_param_throttle_cruise, PSTR("TRIM_THROTTLE")),
|
||||||
|
|
||||||
flight_mode_channel (FLIGHT_MODE_CHANNEL, k_param_flight_mode_channel, PSTR("FLIGHT_MODE_CH")),
|
flight_mode_channel (FLIGHT_MODE_CHANNEL, k_param_flight_mode_channel, PSTR("FLIGHT_MODE_CH")),
|
||||||
flight_modes (k_param_flight_modes, PSTR("FLIGHT_MODES")),
|
flight_modes (k_param_flight_modes, PSTR("FLIGHT_MODES")),
|
||||||
|
|
||||||
pitch_max (PITCH_MAX_CENTIDEGREE, k_param_pitch_max, PSTR("PITCH_MAX_CENTIDEGREE")),
|
pitch_max (PITCH_MAX_CENTIDEGREE, k_param_pitch_max, PSTR("PITCH_MAX_CENTIDEGREE")),
|
||||||
|
|
||||||
log_bitmask (0, k_param_log_bitmask, PSTR("LOG_BITMASK")),
|
log_bitmask (0, k_param_log_bitmask, PSTR("LOG_BITMASK")),
|
||||||
ground_temperature (0, k_param_ground_temperature, PSTR("GND_TEMP")),
|
ground_temperature (0, k_param_ground_temperature, PSTR("GND_TEMP")),
|
||||||
ground_pressure (0, k_param_ground_pressure, PSTR("GND_ABS_PRESS")),
|
ground_pressure (0, k_param_ground_pressure, PSTR("GND_ABS_PRESS")),
|
||||||
RTL_altitude (ALT_HOLD_HOME_CM, k_param_RTL_altitude, PSTR("ALT_HOLD_RTL")),
|
RTL_altitude (ALT_HOLD_HOME_CM, k_param_RTL_altitude, PSTR("ALT_HOLD_RTL")),
|
||||||
|
|
||||||
// RC channel group key name
|
// RC channel group key name
|
||||||
//----------------------------------------------------------------------
|
//----------------------------------------------------------------------
|
||||||
|
@ -255,24 +255,25 @@ public:
|
||||||
rc_6 (k_param_rc_6, PSTR("RC6_")),
|
rc_6 (k_param_rc_6, PSTR("RC6_")),
|
||||||
rc_7 (k_param_rc_7, PSTR("RC7_")),
|
rc_7 (k_param_rc_7, PSTR("RC7_")),
|
||||||
rc_8 (k_param_rc_8, PSTR("RC8_")),
|
rc_8 (k_param_rc_8, PSTR("RC8_")),
|
||||||
|
|
||||||
rc_camera_pitch (k_param_rc_9, PSTR("RC9_")),
|
rc_camera_pitch (k_param_rc_9, PSTR("RC9_")),
|
||||||
rc_camera_roll (k_param_rc_10, PSTR("RC10_")),
|
rc_camera_roll (k_param_rc_10, PSTR("RC10_")),
|
||||||
|
|
||||||
|
|
||||||
// PID controller group key name initial P initial I initial D initial imax
|
// PID controller group key name initial P initial I initial D initial imax
|
||||||
//---------------------------------------------------------------------------------------------------------------------------------------
|
//--------------------------------------------------------------------------------------------------------------------------------------------------------------------
|
||||||
pid_acro_rate_roll (k_param_pid_acro_rate_roll, PSTR("ACR_RLL_"), ACRO_RATE_ROLL_P, ACRO_RATE_ROLL_I, ACRO_RATE_ROLL_D, ACRO_RATE_ROLL_IMAX_CENTIDEGREE),
|
pid_acro_rate_roll (k_param_pid_acro_rate_roll, PSTR("ACR_RLL_"), ACRO_RATE_ROLL_P, ACRO_RATE_ROLL_I, ACRO_RATE_ROLL_D, ACRO_RATE_ROLL_IMAX * 100),
|
||||||
pid_acro_rate_pitch (k_param_pid_acro_rate_pitch, PSTR("ACR_PIT_"), ACRO_RATE_PITCH_P, ACRO_RATE_PITCH_I, ACRO_RATE_PITCH_D, ACRO_RATE_PITCH_IMAX_CENTIDEGREE),
|
pid_acro_rate_pitch (k_param_pid_acro_rate_pitch, PSTR("ACR_PIT_"), ACRO_RATE_PITCH_P, ACRO_RATE_PITCH_I, ACRO_RATE_PITCH_D, ACRO_RATE_PITCH_IMAX * 100),
|
||||||
pid_acro_rate_yaw (k_param_pid_acro_rate_yaw, PSTR("ACR_YAW_"), ACRO_RATE_YAW_P, ACRO_RATE_YAW_I, ACRO_RATE_YAW_D, ACRO_RATE_YAW_IMAX_CENTIDEGREE),
|
pid_acro_rate_yaw (k_param_pid_acro_rate_yaw, PSTR("ACR_YAW_"), ACRO_RATE_YAW_P, ACRO_RATE_YAW_I, ACRO_RATE_YAW_D, ACRO_RATE_YAW_IMAX * 100),
|
||||||
|
|
||||||
pid_stabilize_roll (k_param_pid_stabilize_roll, PSTR("STB_RLL_"), STABILIZE_ROLL_P, STABILIZE_ROLL_I, STABILIZE_ROLL_D, STABILIZE_ROLL_IMAX_CENTIDEGREE),
|
pid_stabilize_roll (k_param_pid_stabilize_roll, PSTR("STB_RLL_"), STABILIZE_ROLL_P, STABILIZE_ROLL_I, STABILIZE_ROLL_D, STABILIZE_ROLL_IMAX * 100),
|
||||||
pid_stabilize_pitch (k_param_pid_stabilize_pitch, PSTR("STB_PIT_"), STABILIZE_PITCH_P, STABILIZE_PITCH_I, STABILIZE_PITCH_D, STABILIZE_PITCH_IMAX_CENTIDEGREE),
|
pid_stabilize_pitch (k_param_pid_stabilize_pitch, PSTR("STB_PIT_"), STABILIZE_PITCH_P, STABILIZE_PITCH_I, STABILIZE_PITCH_D, STABILIZE_PITCH_IMAX * 100),
|
||||||
pid_yaw (k_param_pid_yaw, PSTR("STB_YAW_"), YAW_P, YAW_I, YAW_D, YAW_IMAX_CENTIDEGREE),
|
pid_yaw (k_param_pid_yaw, PSTR("STB_YAW_"), YAW_P, YAW_I, YAW_D, YAW_IMAX * 100),
|
||||||
pid_nav_lat (k_param_pid_nav_lat, PSTR("NAV_LAT_"), NAV_P, NAV_I, NAV_D, NAV_IMAX_CENTIDEGREE),
|
|
||||||
pid_nav_lon (k_param_pid_nav_lon, PSTR("NAV_LON_"), NAV_P, NAV_I, NAV_D, NAV_IMAX_CENTIDEGREE),
|
pid_nav_lat (k_param_pid_nav_lat, PSTR("NAV_LAT_"), NAV_P, NAV_I, NAV_D, NAV_IMAX * 100),
|
||||||
pid_baro_throttle (k_param_pid_baro_throttle, PSTR("THR_BAR_"), THROTTLE_BARO_P, THROTTLE_BARO_I, THROTTLE_BARO_D, THROTTLE_BARO_IMAX_CENTIDEGREE),
|
pid_nav_lon (k_param_pid_nav_lon, PSTR("NAV_LON_"), NAV_P, NAV_I, NAV_D, NAV_IMAX * 100),
|
||||||
pid_sonar_throttle (k_param_pid_sonar_throttle, PSTR("THR_SON_"), THROTTLE_SONAR_P, THROTTLE_SONAR_I, THROTTLE_SONAR_D, THROTTLE_SONAR_IMAX_CENTIDEGREE),
|
|
||||||
|
pid_baro_throttle (k_param_pid_baro_throttle, PSTR("THR_BAR_"), THROTTLE_BARO_P, THROTTLE_BARO_I, THROTTLE_BARO_D, THROTTLE_BARO_IMAX * 100),
|
||||||
|
pid_sonar_throttle (k_param_pid_sonar_throttle, PSTR("THR_SON_"), THROTTLE_SONAR_P, THROTTLE_SONAR_I, THROTTLE_SONAR_D, THROTTLE_SONAR_IMAX * 100),
|
||||||
|
|
||||||
stabilize_dampener (STABILIZE_DAMPENER, k_param_stabilize_dampener, PSTR("STB_DAMP")),
|
stabilize_dampener (STABILIZE_DAMPENER, k_param_stabilize_dampener, PSTR("STB_DAMP")),
|
||||||
hold_yaw_dampener (HOLD_YAW_DAMPENER, k_param_hold_yaw_dampener, PSTR("YAW_DAMP")),
|
hold_yaw_dampener (HOLD_YAW_DAMPENER, k_param_hold_yaw_dampener, PSTR("YAW_DAMP")),
|
||||||
|
|
Loading…
Reference in New Issue