mirror of https://github.com/ArduPilot/ardupilot
Sub: Support changing update period
This commit is contained in:
parent
5491d5bf2d
commit
76c76a6928
|
@ -134,7 +134,9 @@ void Sub::run_rate_controller()
|
|||
{
|
||||
//don't run rate controller in manual or motordetection modes
|
||||
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();
|
||||
}
|
||||
}
|
||||
|
|
|
@ -32,8 +32,8 @@ Sub::Sub()
|
|||
auto_yaw_mode(AUTO_YAW_LOOK_AT_NEXT_WP),
|
||||
inertial_nav(ahrs),
|
||||
ahrs_view(ahrs, ROTATION_NONE),
|
||||
attitude_control(ahrs_view, aparm, motors, scheduler.get_loop_period_s()),
|
||||
pos_control(ahrs_view, inertial_nav, motors, attitude_control, scheduler.get_loop_period_s()),
|
||||
attitude_control(ahrs_view, aparm, motors),
|
||||
pos_control(ahrs_view, inertial_nav, motors, attitude_control),
|
||||
wp_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),
|
||||
|
|
Loading…
Reference in New Issue