mirror of https://github.com/ArduPilot/ardupilot
Copter: Support changing update period in Motors
This commit is contained in:
parent
cc3f2917ea
commit
b6df8e5cb6
|
@ -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);
|
||||
|
||||
|
|
|
@ -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
|
||||
|
|
Loading…
Reference in New Issue