mirror of https://github.com/ArduPilot/ardupilot
synced params
This commit is contained in:
parent
91edeeeef2
commit
574b86b02e
|
@ -32,6 +32,8 @@ static const AP_Param::Info var_info[] PROGMEM = {
|
||||||
GSCALAR(optflow_enabled, "FLOW_ENABLE"),
|
GSCALAR(optflow_enabled, "FLOW_ENABLE"),
|
||||||
GSCALAR(low_voltage, "LOW_VOLT"),
|
GSCALAR(low_voltage, "LOW_VOLT"),
|
||||||
GSCALAR(super_simple, "SUPER_SIMPLE"),
|
GSCALAR(super_simple, "SUPER_SIMPLE"),
|
||||||
|
GSCALAR(rtl_land_enabled, "RTL_LAND"),
|
||||||
|
|
||||||
|
|
||||||
GSCALAR(waypoint_mode, "WP_MODE"),
|
GSCALAR(waypoint_mode, "WP_MODE"),
|
||||||
GSCALAR(command_total, "WP_TOTAL"),
|
GSCALAR(command_total, "WP_TOTAL"),
|
||||||
|
@ -65,6 +67,7 @@ static const AP_Param::Info var_info[] PROGMEM = {
|
||||||
GSCALAR(frame_orientation, "FRAME"),
|
GSCALAR(frame_orientation, "FRAME"),
|
||||||
GSCALAR(top_bottom_ratio, "TB_RATIO"),
|
GSCALAR(top_bottom_ratio, "TB_RATIO"),
|
||||||
GSCALAR(ch7_option, "CH7_OPT"),
|
GSCALAR(ch7_option, "CH7_OPT"),
|
||||||
|
GSCALAR(auto_slew_rate, "AUTO_SLEW"),
|
||||||
|
|
||||||
#if FRAME_CONFIG == HELI_FRAME
|
#if FRAME_CONFIG == HELI_FRAME
|
||||||
GSCALAR(heli_servo_1, "HS1_"),
|
GSCALAR(heli_servo_1, "HS1_"),
|
||||||
|
@ -112,6 +115,10 @@ static const AP_Param::Info var_info[] PROGMEM = {
|
||||||
GGROUP(pid_rate_pitch, "RATE_PIT_", AC_PID),
|
GGROUP(pid_rate_pitch, "RATE_PIT_", AC_PID),
|
||||||
GGROUP(pid_rate_yaw, "RATE_YAW_", AC_PID),
|
GGROUP(pid_rate_yaw, "RATE_YAW_", AC_PID),
|
||||||
|
|
||||||
|
|
||||||
|
GGROUP(pid_loiter_rate_lat, "LOITER_LAT_", AC_PID),
|
||||||
|
GGROUP(pid_loiter_rate_lon, "LOITER_LON_", AC_PID),
|
||||||
|
|
||||||
GGROUP(pid_nav_lat, "NAV_LAT_", AC_PID),
|
GGROUP(pid_nav_lat, "NAV_LAT_", AC_PID),
|
||||||
GGROUP(pid_nav_lon, "NAV_LON_", AC_PID),
|
GGROUP(pid_nav_lon, "NAV_LON_", AC_PID),
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue