Skip to content

Commit

Permalink
Correct optimization param names to line up with optimizer
Browse files Browse the repository at this point in the history
  • Loading branch information
josephward committed Apr 10, 2024
1 parent 9a0167b commit 4d689f3
Show file tree
Hide file tree
Showing 2 changed files with 21 additions and 18 deletions.
38 changes: 21 additions & 17 deletions rosplane_tuning/src/autotune/autotune.py
Original file line number Diff line number Diff line change
Expand Up @@ -157,35 +157,40 @@ def __init__(self):
# As we conduct optimizations, these parameters will be changed to be more
# efficient to optimize the specific gains, based on the design spaces.
if self.get_parameter('current_tuning_autopilot').value == 'roll':
self.optimization_params = {'u1': 1e-3,
'u2': 0.5,
self.optimization_params = {'mu_1': 1e-3,
'mu_2': 0.5,
'sigma': 2.0,
'alpha': 0.05,
'tau': 1e-2}
'tau': 1e-2,
'h': 0.01}
elif self.get_parameter('current_tuning_autopilot').value == 'course':
self.optimization_params = {'u1': 1e-3,
'u2': 0.5,
self.optimization_params = {'mu_1': 1e-3,
'mu_2': 0.5,
'sigma': 2.0,
'alpha': 0.05,
'tau': 1e-2}
'tau': 1e-2,
'h': 0.01}
elif self.get_parameter('current_tuning_autopilot').value == 'pitch':
self.optimization_params = {'u1': 1e-3,
'u2': 0.5,
self.optimization_params = {'mu_1': 1e-3,
'mu_2': 0.5,
'sigma': 2.0,
'alpha': 0.05,
'tau': 1e-2}
'tau': 1e-2,
'h': 0.01}
elif self.get_parameter('current_tuning_autopilot').value == 'altitude':
self.optimization_params = {'u1': 1e-3,
'u2': 0.5,
self.optimization_params = {'mu_1': 1e-3,
'mu_2': 0.5,
'sigma': 2.0,
'alpha': 0.05,
'tau': 1e-2}
'tau': 1e-2,
'h': 0.01}
elif self.get_parameter('current_tuning_autopilot').value == 'airspeed':
self.optimization_params = {'u1': 1e-3,
'u2': 0.5,
self.optimization_params = {'mu_1': 1e-3,
'mu_2': 0.5,
'sigma': 2.0,
'alpha': 0.05,
'tau': 1e-2}
'tau': 1e-2,
'h': 0.01}
else:
raise ValueError(self.get_parameter('current_tuning_autopilot').value +
' is not a valid value for current_tuning_autopilot.' +
Expand All @@ -204,7 +209,7 @@ def state_callback(self, msg):

if self.collecting_data:
time = msg.header.stamp.sec + msg.header.stamp.nanosec * 1e-9
self.state.append([time, msg.va, msg.phi, msg.chi, msg.theta,
self.state.append([time, msg.va, msg.phi, msg.chi, msg.theta,
-msg.position[2]]) # h = -msg.position[2]

def commands_callback(self, msg):
Expand Down Expand Up @@ -597,4 +602,3 @@ def main(args=None):

if __name__ == '__main__':
main()

1 change: 0 additions & 1 deletion rosplane_tuning/src/autotune/optimizer.py
Original file line number Diff line number Diff line change
Expand Up @@ -312,4 +312,3 @@ def interpolate(alpha_1, alpha_2, phi_1, phi_2, phi_1_prime, phi_2_prime):
beta_2 = np.sign(alpha_2 - alpha_1) * np.sqrt(beta_1**2 - phi_1_prime*phi_2_prime)
return alpha_2 - (alpha_2 - alpha_1) \
* (phi_2_prime + beta_2 - beta_1) / (phi_2_prime - phi_1_prime + 2*beta_2)

0 comments on commit 4d689f3

Please sign in to comment.