From 0b79f33c7273c134bcf15e907da4dfc02b9cc8ec Mon Sep 17 00:00:00 2001 From: JMoore5353 Date: Thu, 6 Jun 2024 14:03:32 -0600 Subject: [PATCH] tuned sim parameters --- rosplane/params/anaconda_autopilot_params.yaml | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/rosplane/params/anaconda_autopilot_params.yaml b/rosplane/params/anaconda_autopilot_params.yaml index 85b7c05..b1ea678 100644 --- a/rosplane/params/anaconda_autopilot_params.yaml +++ b/rosplane/params/anaconda_autopilot_params.yaml @@ -3,20 +3,20 @@ autopilot: # node name. alt_hz: 10.0 alt_toz: 5.0 tau: 50.0 - c_kp: 0.8 + c_kp: 3.0 c_kd: 0.0 - c_ki: 0.08 - r_kp: 0.06 - r_kd: 0.04 + c_ki: 0.0 + r_kp: 0.75 + r_kd: 0.1 r_ki: 0.0 - p_kp: -0.3 + p_kp: -0.5 p_kd: -0.095 p_ki: 0.0 p_ff: 0.0 a_t_kp: 0.05 a_t_kd: 0.0 a_t_ki: 0.005 - a_kp: 0.02 + a_kp: 0.1 a_kd: 0.0 a_ki: 0.01 l_kp: .5 @@ -30,7 +30,7 @@ autopilot: # node name. trim_r: 0.0 trim_t: 0.5 max_e: 0.61 - max_a: 0.15 + max_a: 0.60 max_r: 0.523 max_t: 1.0 pwm_rad_e: 1.0 @@ -39,7 +39,7 @@ autopilot: # node name. max_takeoff_throttle: 1.0 mass: 4.5 gravity: 9.8 - max_roll: 25.0 + max_roll: 35.0 frequency: 100 path_manager: