mirror of https://github.com/ArduPilot/ardupilot
Tools: convert ALT_HOLD_RTL and ALT_HOLD_FBWCM
This commit is contained in:
parent
8151647e04
commit
286f6887bd
|
@ -1,4 +1,4 @@
|
|||
ALT_HOLD_RTL 6000
|
||||
RTL_ALTITUDE 60.00
|
||||
ARMING_RUDDER 2
|
||||
AIRSPEED_MAX 17
|
||||
AIRSPEED_MIN 12
|
||||
|
|
|
@ -12,7 +12,7 @@ TRIM_THROTTLE 52
|
|||
LIM_PITCH_MAX 2200
|
||||
LIM_ROLL_CD 3500
|
||||
NAVL1_PERIOD 24
|
||||
ALT_HOLD_RTL 9000
|
||||
RTL_ALTITUDE 90.00
|
||||
FBWB_CLIMB_RATE 5
|
||||
WP_LOITER_RAD 150
|
||||
WP_RADIUS 150
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
|
||||
# https://www.muginuav.com/product/mugin-ev350-carbon-fiber-full-electric-vtol-uav-platform/
|
||||
|
||||
ALT_HOLD_RTL 8000
|
||||
RTL_ALTITUDE 80.00
|
||||
LIM_PITCH_MAX 2000
|
||||
LIM_PITCH_MIN -2000
|
||||
LIM_ROLL_CD 4000
|
||||
|
|
|
@ -16,7 +16,7 @@ GROUND_STEER_ALT,10
|
|||
AIRSPEED_CRUISE,52.00
|
||||
SCALING_SPEED,60
|
||||
TRIM_PITCH_DEG,4
|
||||
ALT_HOLD_RTL,25000
|
||||
RTL_ALTITUDE,250.00
|
||||
FLAP_1_PERCNT,50
|
||||
FLAP_1_SPEED,30
|
||||
RTL_AUTOLAND,2
|
||||
|
|
|
@ -2274,7 +2274,7 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
|||
self.wait_ready_to_arm()
|
||||
self.set_parameters({
|
||||
"FLIGHT_OPTIONS": 0,
|
||||
"ALT_HOLD_RTL": 8000,
|
||||
"RTL_ALTITUDE": 80,
|
||||
"RTL_AUTOLAND": 1,
|
||||
})
|
||||
takeoff_alt = 10
|
||||
|
@ -2282,7 +2282,7 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
|||
self.change_mode("CRUISE")
|
||||
self.wait_distance_to_home(500, 1000, timeout=60)
|
||||
self.change_mode("RTL")
|
||||
expected_alt = self.get_parameter("ALT_HOLD_RTL") / 100.0
|
||||
expected_alt = self.get_parameter("RTL_ALTITUDE")
|
||||
|
||||
home = self.home_position_as_mav_location()
|
||||
distance = self.get_distance(home, self.mav.location())
|
||||
|
@ -2306,7 +2306,7 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
|||
self.wait_ready_to_arm()
|
||||
self.set_parameters({
|
||||
"FLIGHT_OPTIONS": 16,
|
||||
"ALT_HOLD_RTL": 10000,
|
||||
"RTL_ALTITUDE": 100,
|
||||
})
|
||||
self.takeoff(alt=takeoff_alt)
|
||||
self.change_mode("CRUISE")
|
||||
|
@ -2339,7 +2339,7 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
|||
self.wait_distance_to_home(1000, 1500, timeout=60)
|
||||
post_cruise_alt = self.get_altitude(relative=True)
|
||||
self.change_mode('RTL')
|
||||
expected_alt = self.get_parameter("ALT_HOLD_RTL")/100.0
|
||||
expected_alt = self.get_parameter("RTL_ALTITUDE")
|
||||
if expected_alt == -1:
|
||||
expected_alt = self.get_altitude(relative=True)
|
||||
|
||||
|
|
|
@ -1,4 +1,4 @@
|
|||
ALT_HOLD_RTL 20000.0000
|
||||
RTL_ALTITUDE 200.00
|
||||
AIRSPEED_MAX 80.0000
|
||||
AIRSPEED_MIN 25.0000
|
||||
FBWB_CLIMB_RATE 5.0000
|
||||
|
|
|
@ -57,7 +57,7 @@ SERVO12_MIN 1000
|
|||
SERVO12_MAX 2000
|
||||
SERVO11_TRIM 1500
|
||||
RTL_RADIUS 80
|
||||
ALT_HOLD_RTL 2000
|
||||
RTL_ALTITUDE 20.00
|
||||
Q_ENABLE 1
|
||||
Q_FRAME_CLASS 7
|
||||
Q_ANGLE_MAX 4500
|
||||
|
|
|
@ -76,6 +76,6 @@ SERVO12_MIN 1000
|
|||
SERVO12_MAX 2000
|
||||
RTL_RADIUS 80
|
||||
Q_RTL_MODE 1
|
||||
ALT_HOLD_RTL 2000
|
||||
RTL_ALTITUDE 20.00
|
||||
PTCH_RATE_FF 1.407055
|
||||
RLL_RATE_FF 0.552741
|
||||
|
|
|
@ -79,7 +79,7 @@ SERVO12_MIN 1000
|
|||
SERVO12_MAX 2000
|
||||
RTL_RADIUS 80
|
||||
Q_RTL_MODE 1
|
||||
ALT_HOLD_RTL 2000
|
||||
RTL_ALTITUDE 20.00
|
||||
Q_TILT_TYPE 2
|
||||
Q_TILT_YAW_ANGLE 10
|
||||
PTCH_RATE_FF 1.407055
|
||||
|
|
|
@ -74,6 +74,6 @@ Q_A_RAT_RLL_P 0.15
|
|||
Q_A_RAT_PIT_P 0.15
|
||||
Q_A_RAT_RLL_D 0.002
|
||||
Q_A_RAT_PIT_D 0.002
|
||||
ALT_HOLD_RTL 2000
|
||||
RTL_ALTITUDE 20.00
|
||||
PTCH_RATE_FF 1.407055
|
||||
RLL_RATE_FF 0.552741
|
||||
|
|
|
@ -15,8 +15,8 @@ AHRS_TRIM_Y,0
|
|||
AHRS_TRIM_Z,0
|
||||
AHRS_WIND_MAX,0
|
||||
AHRS_YAW_P,0.2
|
||||
ALT_HOLD_FBWCM,0
|
||||
ALT_HOLD_RTL,10000
|
||||
ALT_CRUISE_MIN,0.00
|
||||
RTL_ALTITUDE,100.00
|
||||
ALT_OFFSET,0
|
||||
ARMING_ACCTHRESH,0.75
|
||||
ARMING_CHECK,0
|
||||
|
|
Loading…
Reference in New Issue