@@ -57,25 +57,52 @@ void Mixer::init()
5757void Mixer::param_change_callback (uint16_t param_id)
5858{
5959
60- if ((param_id >=PARAM_PRIMARY_MIXER_OUTPUT_0 )&&(param_id <=PARAM_PRIMARY_MIXER_5_9 )) {
61- load_primary_mixer_values ();
60+ // Follows parameter ordered in mixer.h
61+
62+ if ((param_id >=PARAM_PRIMARY_MIXER_OUTPUT_0 )&&(param_id <=PARAM_PRIMARY_MIXER_OUTPUT_9 )) {
63+ primary_mixer_.output_type [param_id-PARAM_PRIMARY_MIXER_OUTPUT_0] = (output_type_t ) RF_.params_ .get_param_int (param_id);
64+
65+ } else if ((param_id >=PARAM_PRIMARY_MIXER_PWM_RATE_0 )&&(param_id <=PARAM_PRIMARY_MIXER_PWM_RATE_9 )) {
66+ primary_mixer_.default_pwm_rate [param_id-PARAM_PRIMARY_MIXER_PWM_RATE_0] = RF_.params_ .get_param_float (param_id);
67+
68+ } else if ((param_id >=PARAM_PRIMARY_MIXER_0_0 )&&(param_id <=PARAM_PRIMARY_MIXER_5_9 )) {
69+
70+ uint16_t param_id_offset = param_id-PARAM_PRIMARY_MIXER_0_0;
71+ uint16_t parma_id_row = param_id_offset%6 ;
72+ uint16_t parma_id_col = param_id_offset/6 ;
73+
74+ if (parma_id_row==0 ) { primary_mixer_.Fx [parma_id_col] = RF_.params_ .get_param_float (param_id); }
75+ if (parma_id_row==1 ) { primary_mixer_.Fy [parma_id_col] = RF_.params_ .get_param_float (param_id); }
76+ if (parma_id_row==2 ) { primary_mixer_.Fz [parma_id_col] = RF_.params_ .get_param_float (param_id); }
77+ if (parma_id_row==3 ) { primary_mixer_.Qx [parma_id_col] = RF_.params_ .get_param_float (param_id); }
78+ if (parma_id_row==4 ) { primary_mixer_.Qy [parma_id_col] = RF_.params_ .get_param_float (param_id); }
79+ if (parma_id_row==5 ) { primary_mixer_.Qz [parma_id_col] = RF_.params_ .get_param_float (param_id); }
80+
6281 } else if ((param_id >=PARAM_SECONDARY_MIXER_0_0 )&&(param_id <=PARAM_SECONDARY_MIXER_5_9 )) {
63- load_secondary_mixer_values ();
82+
83+ uint16_t param_id_offset = param_id-PARAM_SECONDARY_MIXER_0_0;
84+ uint16_t parma_id_row = param_id_offset%6 ;
85+ uint16_t parma_id_col = param_id_offset/6 ;
86+ if (parma_id_row==0 ) { secondary_mixer_.Fx [parma_id_col] = RF_.params_ .get_param_float (param_id); }
87+ if (parma_id_row==1 ) { secondary_mixer_.Fy [parma_id_col] = RF_.params_ .get_param_float (param_id); }
88+ if (parma_id_row==2 ) { secondary_mixer_.Fz [parma_id_col] = RF_.params_ .get_param_float (param_id); }
89+ if (parma_id_row==3 ) { secondary_mixer_.Qx [parma_id_col] = RF_.params_ .get_param_float (param_id); }
90+ if (parma_id_row==4 ) { secondary_mixer_.Qy [parma_id_col] = RF_.params_ .get_param_float (param_id); }
91+ if (parma_id_row==5 ) { secondary_mixer_.Qz [parma_id_col] = RF_.params_ .get_param_float (param_id); }
92+
6493 } else switch (param_id) {
6594 case PARAM_PRIMARY_MIXER:
6695 case PARAM_SECONDARY_MIXER:
6796 init_mixing ();
6897 break ;
69- case PARAM_MOTOR_RESISTANCE:
70- case PARAM_MOTOR_KV:
71- case PARAM_NO_LOAD_CURRENT:
72- case PARAM_PROP_DIAMETER:
73- case PARAM_PROP_CT:
74- case PARAM_PROP_CQ:
75- case PARAM_NUM_MOTORS:
76- case PARAM_VOLT_MAX:
77- update_parameters ();
78- break ;
98+ case PARAM_MOTOR_RESISTANCE: R_ = RF_.params_ .get_param_float (PARAM_MOTOR_RESISTANCE); break ;
99+ case PARAM_MOTOR_KV: K_V_ = RF_.params_ .get_param_float (PARAM_MOTOR_KV); K_Q_ = K_V_; break ;
100+ case PARAM_NO_LOAD_CURRENT: i_0_ = RF_.params_ .get_param_float (PARAM_NO_LOAD_CURRENT); break ;
101+ case PARAM_PROP_DIAMETER: D_ = RF_.params_ .get_param_float (PARAM_PROP_DIAMETER); break ;
102+ case PARAM_PROP_CT: C_T_ = RF_.params_ .get_param_float (PARAM_PROP_CT); break ;
103+ case PARAM_PROP_CQ: C_Q_ = RF_.params_ .get_param_float (PARAM_PROP_CQ); break ;
104+ case PARAM_NUM_MOTORS: num_motors_ = RF_.params_ .get_param_int (PARAM_NUM_MOTORS); break ;
105+ case PARAM_VOLT_MAX: V_max_ = RF_.params_ .get_param_float (PARAM_VOLT_MAX); break ;
79106 case PARAM_MOTOR_PWM_SEND_RATE:
80107 init_PWM ();
81108 break ;
@@ -85,6 +112,7 @@ void Mixer::param_change_callback(uint16_t param_id)
85112 }
86113}
87114
115+
88116void Mixer::init_mixing ()
89117{
90118 // clear the invalid mixer error
0 commit comments