Sub: Add support for AP_AHRS_View
This commit is contained in:
parent
68a7534f2c
commit
84c3c0d234
@ -61,15 +61,16 @@ Sub::Sub(void) :
|
||||
condition_start(0),
|
||||
G_Dt(MAIN_LOOP_SECONDS),
|
||||
inertial_nav(ahrs),
|
||||
attitude_control(ahrs, aparm, motors, MAIN_LOOP_SECONDS),
|
||||
pos_control(ahrs, inertial_nav, motors, attitude_control,
|
||||
ahrs_view(ahrs, ROTATION_NONE),
|
||||
attitude_control(ahrs_view, aparm, motors, MAIN_LOOP_SECONDS),
|
||||
pos_control(ahrs_view, inertial_nav, motors, attitude_control,
|
||||
g.p_alt_hold, g.p_vel_z, g.pid_accel_z,
|
||||
g.p_pos_xy, g.pi_vel_xy),
|
||||
#if AVOIDANCE_ENABLED == ENABLED
|
||||
avoid(ahrs, inertial_nav, fence, g2.proximity),
|
||||
#endif
|
||||
wp_nav(inertial_nav, ahrs, pos_control, attitude_control),
|
||||
circle_nav(inertial_nav, ahrs, pos_control),
|
||||
wp_nav(inertial_nav, ahrs_view, pos_control, attitude_control),
|
||||
circle_nav(inertial_nav, ahrs_view, pos_control),
|
||||
pmTest1(0),
|
||||
fast_loopTimer(0),
|
||||
mainLoop_count(0),
|
||||
|
@ -401,6 +401,8 @@ private:
|
||||
// Inertial Navigation
|
||||
AP_InertialNav_NavEKF inertial_nav;
|
||||
|
||||
AP_AHRS_View ahrs_view;
|
||||
|
||||
// Attitude, Position and Waypoint navigation objects
|
||||
// To-Do: move inertial nav up or other navigation variables down here
|
||||
AC_AttitudeControl_Sub attitude_control;
|
||||
|
Loading…
Reference in New Issue
Block a user