diff --git a/ArduSub/ArduSub.cpp b/ArduSub/ArduSub.cpp index 9537705eba..3d8ab6fe04 100644 --- a/ArduSub/ArduSub.cpp +++ b/ArduSub/ArduSub.cpp @@ -275,9 +275,6 @@ void Sub::one_hz_loop() // update assigned functions and enable auxiliary servos SRV_Channels::enable_aux_servos(); - // update position controller alt limits - update_poscon_alt_max(); - // log terrain data terrain_logging(); diff --git a/ArduSub/Attitude.cpp b/ArduSub/Attitude.cpp index c5dbc67e73..519d97f7c3 100644 --- a/ArduSub/Attitude.cpp +++ b/ArduSub/Attitude.cpp @@ -163,29 +163,6 @@ float Sub::get_surface_tracking_climb_rate(int16_t target_rate, float current_al #endif } -// updates position controller's maximum altitude using fence and EKF limits -void Sub::update_poscon_alt_max() -{ - // minimum altitude, ie. maximum depth - // interpreted as no limit if left as zero - float min_alt_cm = 0.0; - - // no limit if greater than 100, a limit is necessary, - // or the vehicle will try to fly out of the water - float max_alt_cm = g.surface_depth; // minimum depth - -#if AC_FENCE == ENABLED - // set fence altitude limit in position controller - if ((fence.get_enabled_fences() & AC_FENCE_TYPE_ALT_MAX) != 0) { - min_alt_cm = fence.get_safe_alt_min()*100.0f; - max_alt_cm = fence.get_safe_alt_max()*100.0f; - } -#endif - // pass limit to pos controller - pos_control.set_alt_min(min_alt_cm); - pos_control.set_alt_max(max_alt_cm); -} - // rotate vector from vehicle's perspective to North-East frame void Sub::rotate_body_frame_to_NE(float &x, float &y) { diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index 2a061b8474..8028542f06 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -46,7 +46,7 @@ #include #include // Mission command library #include // Attitude control library -#include // Position control library +#include // Position control library #include // AP Motors library #include // Filter library #include // APM relay @@ -328,7 +328,7 @@ private: // To-Do: move inertial nav up or other navigation variables down here AC_AttitudeControl_Sub attitude_control; - AC_PosControl_Sub pos_control; + AC_PosControl pos_control; AC_WPNav wp_nav; AC_Loiter loiter_nav; @@ -401,7 +401,6 @@ private: float get_look_ahead_yaw(); float get_pilot_desired_climb_rate(float throttle_control); float get_surface_tracking_climb_rate(int16_t target_rate, float current_alt_target, float dt); - void update_poscon_alt_max(); void rotate_body_frame_to_NE(float &x, float &y); void Log_Write_Control_Tuning(); void Log_Write_Attitude();