From cae16d79bde5f070ef68931c60b0e7a879391e47 Mon Sep 17 00:00:00 2001 From: Ian Reid Date: Thu, 22 Aug 2024 10:12:57 -0600 Subject: [PATCH] Fixed the motor parameters. --- rosflight_sim/params/multirotor_dynamics.yaml | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/rosflight_sim/params/multirotor_dynamics.yaml b/rosflight_sim/params/multirotor_dynamics.yaml index f23c1ea..c80aa0c 100644 --- a/rosflight_sim/params/multirotor_dynamics.yaml +++ b/rosflight_sim/params/multirotor_dynamics.yaml @@ -19,14 +19,14 @@ # Prop Model # Thrust - CT_0: 0.1196850 - CT_1: 0.0399995 - CT_2: -0.400139 + CT_0: 0.08729101 + CT_1: -0.11006411 + CT_2: -0.12928596 # Torque - CQ_0: 0.0097976 - CQ_1: -0.012271 - CQ_2: -0.014743 + CQ_0: 0.00428594 + CQ_1: 0.00146105 + CQ_2: -0.01440988 # Diameter (m) D_prop: 0.381