From b6df8e5cb6641d6886a4e43abda51d631a1b11e6 Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Mon, 5 Dec 2022 16:56:42 +1030 Subject: [PATCH] Copter: Support changing update period in Motors --- ArduCopter/Attitude.cpp | 1 + ArduCopter/radio.cpp | 1 - 2 files changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/Attitude.cpp b/ArduCopter/Attitude.cpp index 1a575358f3..deee31f0e3 100644 --- a/ArduCopter/Attitude.cpp +++ b/ArduCopter/Attitude.cpp @@ -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); diff --git a/ArduCopter/radio.cpp b/ArduCopter/radio.cpp index b71ade1666..e7360c0890 100644 --- a/ArduCopter/radio.cpp +++ b/ArduCopter/radio.cpp @@ -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