Sub: use scheduler.get_loop_period_s() instead of MAIN_LOOP_SECONDS

This commit is contained in:
Willian Galvani 2021-07-06 16:10:33 -03:00
parent 2fb939a1ca
commit 66ad7ff8e7
2 changed files with 2 additions and 3 deletions

View File

@ -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, MAIN_LOOP_SECONDS),
pos_control(ahrs_view, inertial_nav, motors, attitude_control, MAIN_LOOP_SECONDS),
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()),
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),

View File

@ -14,7 +14,6 @@
// run at 400Hz on all systems
# define MAIN_LOOP_RATE 400
# define MAIN_LOOP_SECONDS 0.0025f
#ifndef SURFACE_DEPTH_DEFAULT
# define SURFACE_DEPTH_DEFAULT -10.0f // pressure sensor reading 10cm depth means craft is considered surfaced