mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Copter: remove MAIN_LOOP_RATE in favour of parameter value
This commit is contained in:
parent
d541ac509f
commit
89e6e70235
@ -99,7 +99,7 @@ Copter::Copter(void) :
|
|||||||
#endif
|
#endif
|
||||||
#if FRAME_CONFIG == HELI_FRAME
|
#if FRAME_CONFIG == HELI_FRAME
|
||||||
// ToDo: Input Manager is only used by Heli for 3.3, but will be used by all frames for 3.4
|
// ToDo: Input Manager is only used by Heli for 3.3, but will be used by all frames for 3.4
|
||||||
input_manager(MAIN_LOOP_RATE),
|
input_manager(),
|
||||||
#endif
|
#endif
|
||||||
in_mavlink_delay(false),
|
in_mavlink_delay(false),
|
||||||
gcs_out_of_time(false),
|
gcs_out_of_time(false),
|
||||||
|
@ -49,7 +49,6 @@
|
|||||||
#define MAGNETOMETER ENABLED
|
#define MAGNETOMETER ENABLED
|
||||||
|
|
||||||
// run at 400Hz on all systems
|
// run at 400Hz on all systems
|
||||||
# define MAIN_LOOP_RATE 400
|
|
||||||
# define MAIN_LOOP_SECONDS 0.0025f
|
# define MAIN_LOOP_SECONDS 0.0025f
|
||||||
|
|
||||||
#ifndef ARMING_DELAY_SEC
|
#ifndef ARMING_DELAY_SEC
|
||||||
|
@ -117,7 +117,10 @@ void Copter::init_ardupilot()
|
|||||||
// trad heli specific initialisation
|
// trad heli specific initialisation
|
||||||
heli_init();
|
heli_init();
|
||||||
#endif
|
#endif
|
||||||
|
#if FRAME_CONFIG == HELI_FRAME
|
||||||
|
input_manager.set_loop_rate(scheduler.get_loop_rate_hz());
|
||||||
|
#endif
|
||||||
|
|
||||||
init_rc_in(); // sets up rc channels from radio
|
init_rc_in(); // sets up rc channels from radio
|
||||||
|
|
||||||
// default frame class to match firmware if possible
|
// default frame class to match firmware if possible
|
||||||
@ -515,36 +518,36 @@ void Copter::allocate_motors(void)
|
|||||||
case AP_Motors::MOTOR_FRAME_OCTAQUAD:
|
case AP_Motors::MOTOR_FRAME_OCTAQUAD:
|
||||||
case AP_Motors::MOTOR_FRAME_DODECAHEXA:
|
case AP_Motors::MOTOR_FRAME_DODECAHEXA:
|
||||||
default:
|
default:
|
||||||
motors = new AP_MotorsMatrix(MAIN_LOOP_RATE);
|
motors = new AP_MotorsMatrix(copter.scheduler.get_loop_rate_hz());
|
||||||
motors_var_info = AP_MotorsMatrix::var_info;
|
motors_var_info = AP_MotorsMatrix::var_info;
|
||||||
break;
|
break;
|
||||||
case AP_Motors::MOTOR_FRAME_TRI:
|
case AP_Motors::MOTOR_FRAME_TRI:
|
||||||
motors = new AP_MotorsTri(MAIN_LOOP_RATE);
|
motors = new AP_MotorsTri(copter.scheduler.get_loop_rate_hz());
|
||||||
motors_var_info = AP_MotorsTri::var_info;
|
motors_var_info = AP_MotorsTri::var_info;
|
||||||
AP_Param::set_frame_type_flags(AP_PARAM_FRAME_TRICOPTER);
|
AP_Param::set_frame_type_flags(AP_PARAM_FRAME_TRICOPTER);
|
||||||
break;
|
break;
|
||||||
case AP_Motors::MOTOR_FRAME_SINGLE:
|
case AP_Motors::MOTOR_FRAME_SINGLE:
|
||||||
motors = new AP_MotorsSingle(MAIN_LOOP_RATE);
|
motors = new AP_MotorsSingle(copter.scheduler.get_loop_rate_hz());
|
||||||
motors_var_info = AP_MotorsSingle::var_info;
|
motors_var_info = AP_MotorsSingle::var_info;
|
||||||
break;
|
break;
|
||||||
case AP_Motors::MOTOR_FRAME_COAX:
|
case AP_Motors::MOTOR_FRAME_COAX:
|
||||||
motors = new AP_MotorsCoax(MAIN_LOOP_RATE);
|
motors = new AP_MotorsCoax(copter.scheduler.get_loop_rate_hz());
|
||||||
motors_var_info = AP_MotorsCoax::var_info;
|
motors_var_info = AP_MotorsCoax::var_info;
|
||||||
break;
|
break;
|
||||||
case AP_Motors::MOTOR_FRAME_TAILSITTER:
|
case AP_Motors::MOTOR_FRAME_TAILSITTER:
|
||||||
motors = new AP_MotorsTailsitter(MAIN_LOOP_RATE);
|
motors = new AP_MotorsTailsitter(copter.scheduler.get_loop_rate_hz());
|
||||||
motors_var_info = AP_MotorsTailsitter::var_info;
|
motors_var_info = AP_MotorsTailsitter::var_info;
|
||||||
break;
|
break;
|
||||||
#else // FRAME_CONFIG == HELI_FRAME
|
#else // FRAME_CONFIG == HELI_FRAME
|
||||||
case AP_Motors::MOTOR_FRAME_HELI_DUAL:
|
case AP_Motors::MOTOR_FRAME_HELI_DUAL:
|
||||||
motors = new AP_MotorsHeli_Dual(MAIN_LOOP_RATE);
|
motors = new AP_MotorsHeli_Dual(copter.scheduler.get_loop_rate_hz());
|
||||||
motors_var_info = AP_MotorsHeli_Dual::var_info;
|
motors_var_info = AP_MotorsHeli_Dual::var_info;
|
||||||
AP_Param::set_frame_type_flags(AP_PARAM_FRAME_HELI);
|
AP_Param::set_frame_type_flags(AP_PARAM_FRAME_HELI);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case AP_Motors::MOTOR_FRAME_HELI:
|
case AP_Motors::MOTOR_FRAME_HELI:
|
||||||
default:
|
default:
|
||||||
motors = new AP_MotorsHeli_Single(MAIN_LOOP_RATE);
|
motors = new AP_MotorsHeli_Single(copter.scheduler.get_loop_rate_hz());
|
||||||
motors_var_info = AP_MotorsHeli_Single::var_info;
|
motors_var_info = AP_MotorsHeli_Single::var_info;
|
||||||
AP_Param::set_frame_type_flags(AP_PARAM_FRAME_HELI);
|
AP_Param::set_frame_type_flags(AP_PARAM_FRAME_HELI);
|
||||||
break;
|
break;
|
||||||
|
Loading…
Reference in New Issue
Block a user