Tracker: remove unused servo_limit structure

This commit is contained in:
Randy Mackay 2016-06-22 10:13:08 +09:00
parent 2b7203e4d1
commit df55760d77
1 changed files with 0 additions and 8 deletions

View File

@ -167,14 +167,6 @@ private:
bool scan_reverse_yaw : 1;// controls direction of yaw movement in SCAN mode
} nav_status = {0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, false, false, true, false, false};
// Servo state
struct {
bool yaw_lower : 1; // true if yaw servo has been limited from moving to a lower position (i.e. position or rate limited)
bool yaw_upper : 1; // true if yaw servo has been limited from moving to a higher position (i.e. position or rate limited)
bool pitch_lower : 1; // true if pitch servo has been limited from moving to a lower position (i.e. position or rate limited)
bool pitch_upper : 1; // true if pitch servo has been limited from moving to a higher position (i.e. position or rate limited)
} servo_limit = {true, true, true, true};
// setup the var_info table
AP_Param param_loader{var_info};