Sub: Support changing update period

This commit is contained in:
Leonard Hall 2022-11-30 15:56:14 +10:30 committed by Randy Mackay
parent 2ceec6b17d
commit f8d4f6afc9
2 changed files with 5 additions and 3 deletions

View File

@ -134,7 +134,9 @@ void Sub::run_rate_controller()
{ {
//don't run rate controller in manual or motordetection modes //don't run rate controller in manual or motordetection modes
if (control_mode != MANUAL && control_mode != MOTOR_DETECT) { if (control_mode != MANUAL && control_mode != MOTOR_DETECT) {
// run low level rate controllers that only require IMU data // 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());
attitude_control.rate_controller_run(); attitude_control.rate_controller_run();
} }
} }

View File

@ -32,8 +32,8 @@ Sub::Sub()
auto_yaw_mode(AUTO_YAW_LOOK_AT_NEXT_WP), auto_yaw_mode(AUTO_YAW_LOOK_AT_NEXT_WP),
inertial_nav(ahrs), inertial_nav(ahrs),
ahrs_view(ahrs, ROTATION_NONE), ahrs_view(ahrs, ROTATION_NONE),
attitude_control(ahrs_view, aparm, motors, scheduler.get_loop_period_s()), attitude_control(ahrs_view, aparm, motors),
pos_control(ahrs_view, inertial_nav, motors, attitude_control, scheduler.get_loop_period_s()), pos_control(ahrs_view, inertial_nav, motors, attitude_control),
wp_nav(inertial_nav, ahrs_view, pos_control, attitude_control), wp_nav(inertial_nav, ahrs_view, pos_control, attitude_control),
loiter_nav(inertial_nav, ahrs_view, pos_control, attitude_control), loiter_nav(inertial_nav, ahrs_view, pos_control, attitude_control),
circle_nav(inertial_nav, ahrs_view, pos_control), circle_nav(inertial_nav, ahrs_view, pos_control),