mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Sub: use scheduler.get_loop_period_s() instead of MAIN_LOOP_SECONDS
This commit is contained in:
parent
2fb939a1ca
commit
66ad7ff8e7
@ -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, MAIN_LOOP_SECONDS),
|
attitude_control(ahrs_view, aparm, motors, scheduler.get_loop_period_s()),
|
||||||
pos_control(ahrs_view, inertial_nav, motors, attitude_control, MAIN_LOOP_SECONDS),
|
pos_control(ahrs_view, inertial_nav, motors, attitude_control, scheduler.get_loop_period_s()),
|
||||||
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),
|
||||||
|
@ -14,7 +14,6 @@
|
|||||||
|
|
||||||
// run at 400Hz on all systems
|
// run at 400Hz on all systems
|
||||||
# define MAIN_LOOP_RATE 400
|
# define MAIN_LOOP_RATE 400
|
||||||
# define MAIN_LOOP_SECONDS 0.0025f
|
|
||||||
|
|
||||||
#ifndef SURFACE_DEPTH_DEFAULT
|
#ifndef SURFACE_DEPTH_DEFAULT
|
||||||
# define SURFACE_DEPTH_DEFAULT -10.0f // pressure sensor reading 10cm depth means craft is considered surfaced
|
# define SURFACE_DEPTH_DEFAULT -10.0f // pressure sensor reading 10cm depth means craft is considered surfaced
|
||||||
|
Loading…
Reference in New Issue
Block a user