Copter: Support changing update period in Motors

This commit is contained in:
Leonard Hall 2022-12-05 16:56:42 +10:30 committed by Andrew Tridgell
parent 685984cc8f
commit 582f38de76
2 changed files with 1 additions and 1 deletions

View File

@ -10,6 +10,7 @@ void Copter::run_rate_controller()
{
// set attitude and position controller loop time
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);

View File

@ -41,7 +41,6 @@ void Copter::init_rc_in()
// init_rc_out -- initialise motors
void Copter::init_rc_out()
{
motors->set_loop_rate(scheduler.get_loop_rate_hz());
motors->init((AP_Motors::motor_frame_class)g2.frame_class.get(), (AP_Motors::motor_frame_type)g.frame_type.get());
// enable aux servos to cope with multiple output channels per motor