diff --git a/rosplane_tuning/src/autotune/autotune.py b/rosplane_tuning/src/autotune/autotune.py index 43dea1f..815d544 100644 --- a/rosplane_tuning/src/autotune/autotune.py +++ b/rosplane_tuning/src/autotune/autotune.py @@ -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.' + @@ -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): @@ -597,4 +602,3 @@ def main(args=None): if __name__ == '__main__': main() - diff --git a/rosplane_tuning/src/autotune/optimizer.py b/rosplane_tuning/src/autotune/optimizer.py index 4b803d9..d04f6a0 100644 --- a/rosplane_tuning/src/autotune/optimizer.py +++ b/rosplane_tuning/src/autotune/optimizer.py @@ -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) -