mirror of https://github.com/ArduPilot/ardupilot
Tracker: move nav_status lower in AntennaTracker.pde
No functional change
This commit is contained in:
parent
b9eaec8e97
commit
1786c36457
|
@ -102,20 +102,6 @@ static AP_Scheduler scheduler;
|
|||
// notification object for LEDs, buzzers etc
|
||||
static AP_Notify notify;
|
||||
|
||||
// tracking status for MAVLink
|
||||
static struct {
|
||||
float bearing; // bearing to vehicle in centi-degrees
|
||||
float distance; // distance to vehicle in meters
|
||||
float pitch; // pitch to vehicle in degrees (positive means vehicle is above tracker, negative means below)
|
||||
float altitude_difference; // altitude difference between tracker and vehicle in meters. positive value means vehicle is above tracker
|
||||
float altitude_offset; // offset in meters which is added to tracker altitude to align altitude measurements with vehicle's barometer
|
||||
bool manual_control_yaw : 1;// true if tracker yaw is under manual control
|
||||
bool manual_control_pitch : 1;// true if tracker pitch is manually controlled
|
||||
bool need_altitude_calibration : 1;// true if tracker altitude has not been determined (true after startup)
|
||||
bool scan_reverse_pitch : 1;// controls direction of pitch movement in SCAN mode
|
||||
bool scan_reverse_yaw : 1;// controls direction of yaw movement in SCAN mode
|
||||
} nav_status;
|
||||
|
||||
static uint32_t start_time_ms;
|
||||
|
||||
static bool usb_connected;
|
||||
|
@ -235,6 +221,22 @@ static struct {
|
|||
float ground_speed; // vehicle's last known ground speed in m/s
|
||||
} vehicle;
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// Navigation controller state
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
static struct {
|
||||
float bearing; // bearing to vehicle in centi-degrees
|
||||
float distance; // distance to vehicle in meters
|
||||
float pitch; // pitch to vehicle in degrees (positive means vehicle is above tracker, negative means below)
|
||||
float altitude_difference; // altitude difference between tracker and vehicle in meters. positive value means vehicle is above tracker
|
||||
float altitude_offset; // offset in meters which is added to tracker altitude to align altitude measurements with vehicle's barometer
|
||||
bool manual_control_yaw : 1;// true if tracker yaw is under manual control
|
||||
bool manual_control_pitch : 1;// true if tracker pitch is manually controlled
|
||||
bool need_altitude_calibration : 1;// true if tracker altitude has not been determined (true after startup)
|
||||
bool scan_reverse_pitch : 1;// controls direction of pitch movement in SCAN mode
|
||||
bool scan_reverse_yaw : 1;// controls direction of yaw movement in SCAN mode
|
||||
} nav_status;
|
||||
|
||||
/*
|
||||
scheduler table - all regular tasks apart from the fast_loop()
|
||||
should be listed here, along with how often they should be called
|
||||
|
|
Loading…
Reference in New Issue