|
|
@ -46,7 +46,7 @@ |
|
|
|
#include <AP_AHRS/AP_AHRS.h> |
|
|
|
#include <AP_AHRS/AP_AHRS.h> |
|
|
|
#include <AP_Mission/AP_Mission.h> // Mission command library |
|
|
|
#include <AP_Mission/AP_Mission.h> // Mission command library |
|
|
|
#include <AC_AttitudeControl/AC_AttitudeControl_Sub.h> // Attitude control library |
|
|
|
#include <AC_AttitudeControl/AC_AttitudeControl_Sub.h> // Attitude control library |
|
|
|
#include <AC_AttitudeControl/AC_PosControl_Sub.h> // Position control library |
|
|
|
#include <AC_AttitudeControl/AC_PosControl.h> // Position control library |
|
|
|
#include <AP_Motors/AP_Motors.h> // AP Motors library |
|
|
|
#include <AP_Motors/AP_Motors.h> // AP Motors library |
|
|
|
#include <Filter/Filter.h> // Filter library |
|
|
|
#include <Filter/Filter.h> // Filter library |
|
|
|
#include <AP_Relay/AP_Relay.h> // APM relay |
|
|
|
#include <AP_Relay/AP_Relay.h> // APM relay |
|
|
@ -328,7 +328,7 @@ private: |
|
|
|
// To-Do: move inertial nav up or other navigation variables down here
|
|
|
|
// To-Do: move inertial nav up or other navigation variables down here
|
|
|
|
AC_AttitudeControl_Sub attitude_control; |
|
|
|
AC_AttitudeControl_Sub attitude_control; |
|
|
|
|
|
|
|
|
|
|
|
AC_PosControl_Sub pos_control; |
|
|
|
AC_PosControl pos_control; |
|
|
|
|
|
|
|
|
|
|
|
AC_WPNav wp_nav; |
|
|
|
AC_WPNav wp_nav; |
|
|
|
AC_Loiter loiter_nav; |
|
|
|
AC_Loiter loiter_nav; |
|
|
@ -401,7 +401,6 @@ private: |
|
|
|
float get_look_ahead_yaw(); |
|
|
|
float get_look_ahead_yaw(); |
|
|
|
float get_pilot_desired_climb_rate(float throttle_control); |
|
|
|
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); |
|
|
|
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 rotate_body_frame_to_NE(float &x, float &y); |
|
|
|
void Log_Write_Control_Tuning(); |
|
|
|
void Log_Write_Control_Tuning(); |
|
|
|
void Log_Write_Attitude(); |
|
|
|
void Log_Write_Attitude(); |
|
|
|