mirror of https://github.com/ArduPilot/ardupilot
Plane: Support changing update period in Motors
This commit is contained in:
parent
231fc2b18b
commit
16ccdeb058
|
@ -682,12 +682,12 @@ bool QuadPlane::setup(void)
|
|||
|
||||
switch ((AP_Motors::motor_frame_class)frame_class) {
|
||||
case AP_Motors::MOTOR_FRAME_TRI:
|
||||
motors = new AP_MotorsTri(plane.scheduler.get_loop_rate_hz(), rc_speed);
|
||||
motors = new AP_MotorsTri(rc_speed);
|
||||
motors_var_info = AP_MotorsTri::var_info;
|
||||
break;
|
||||
case AP_Motors::MOTOR_FRAME_TAILSITTER:
|
||||
// this is a duo-motor tailsitter
|
||||
tailsitter.tailsitter_motors = new AP_MotorsTailsitter(plane.scheduler.get_loop_rate_hz(), rc_speed);
|
||||
tailsitter.tailsitter_motors = new AP_MotorsTailsitter(rc_speed);
|
||||
motors = tailsitter.tailsitter_motors;
|
||||
motors_var_info = AP_MotorsTailsitter::var_info;
|
||||
break;
|
||||
|
@ -698,7 +698,7 @@ bool QuadPlane::setup(void)
|
|||
#endif // AP_SCRIPTING_ENABLED
|
||||
break;
|
||||
default:
|
||||
motors = new AP_MotorsMatrix(plane.scheduler.get_loop_rate_hz(), rc_speed);
|
||||
motors = new AP_MotorsMatrix(rc_speed);
|
||||
motors_var_info = AP_MotorsMatrix::var_info;
|
||||
break;
|
||||
}
|
||||
|
@ -1986,8 +1986,10 @@ void QuadPlane::motors_output(bool run_rate_controller)
|
|||
relax_attitude_control();
|
||||
}
|
||||
// run low level rate controllers that only require IMU data and set loop time
|
||||
attitude_control->set_dt(AP::scheduler().get_last_loop_time_s());
|
||||
pos_control->set_dt(AP::scheduler().get_last_loop_time_s());
|
||||
const float last_loop_time_s = AP::scheduler().get_last_loop_time_s();
|
||||
motors->set_dt(last_loop_time_s);
|
||||
attitude_control->set_dt(last_loop_time_s);
|
||||
pos_control->set_dt(last_loop_time_s);
|
||||
attitude_control->rate_controller_run();
|
||||
last_att_control_ms = now;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue