AP_GPS: Improve comments and documentation (NFC)

This commit is contained in:
Dr.-Ing. Amilcar Do Carmo Lucas 2017-07-01 20:17:24 +02:00 committed by Randy Mackay
parent efa59d47f2
commit 059c213d19
4 changed files with 46 additions and 46 deletions

View File

@ -134,9 +134,9 @@ public:
uint16_t vdop; ///< vertical dilution of precision in cm
uint8_t num_sats; ///< Number of visible satellites
Vector3f velocity; ///< 3D velocity in m/s, in NED format
float speed_accuracy; ///< 3D velocity accuracy estimate in m/s
float horizontal_accuracy; ///< horizontal accuracy estimate in m
float vertical_accuracy; ///< vertical accuracy estimate in m
float speed_accuracy; ///< 3D velocity RMS accuracy estimate in m/s
float horizontal_accuracy; ///< horizontal RMS accuracy estimate in m
float vertical_accuracy; ///< vertical RMS accuracy estimate in m
bool have_vertical_velocity:1; ///< does GPS give vertical velocity? Set to true only once available.
bool have_speed_accuracy:1; ///< does GPS give speed accuracy? Set to true only once available.
bool have_horizontal_accuracy:1; ///< does GPS give horizontal position accuracy? Set to true only once available.
@ -297,7 +297,7 @@ public:
return last_message_time_ms(primary_instance);
}
// return true if the GPS supports vertical velocity values
// return true if the GPS supports vertical velocity values
bool have_vertical_velocity(uint8_t instance) const {
return state[instance].have_vertical_velocity;
}
@ -398,7 +398,7 @@ protected:
private:
// returns the desired gps update rate in milliseconds
// this does not provide any gurantee that the GPS is updating at the requested
// this does not provide any guarantee that the GPS is updating at the requested
// rate it is simply a helper for use in the backends for determining what rate
// they should be configuring the GPS to run at
uint16_t get_rate_ms(uint8_t instance) const;
@ -407,7 +407,7 @@ private:
// the time we got our last fix in system milliseconds
uint32_t last_fix_time_ms;
// the time we got our last fix in system milliseconds
// the time we got our last message in system milliseconds
uint32_t last_message_time_ms;
};
// Note allowance for an additional instance to contain blended data

View File

@ -46,42 +46,42 @@ private:
uint16_t length;
};
struct PACKED erb_ver {
uint32_t time;
uint32_t time; ///< GPS time of week of the navigation epoch [ms]
uint8_t ver_high;
uint8_t ver_medium;
uint8_t ver_low;
};
struct PACKED erb_pos {
uint32_t time;
uint32_t time; ///< GPS time of week of the navigation epoch [ms]
double longitude;
double latitude;
double altitude_ellipsoid;
double altitude_msl;
uint32_t horizontal_accuracy;
uint32_t vertical_accuracy;
double altitude_ellipsoid; ///< Height above ellipsoid [m]
double altitude_msl; ///< Height above mean sea level [m]
uint32_t horizontal_accuracy; ///< Horizontal accuracy estimate [mm]
uint32_t vertical_accuracy; ///< Vertical accuracy estimate [mm]
};
struct PACKED erb_stat {
uint32_t time;
uint32_t time; ///< GPS time of week of the navigation epoch [ms]
uint16_t week;
uint8_t fix_type;
uint8_t fix_type; ///< see erb_fix_type enum
uint8_t fix_status;
uint8_t satellites;
};
struct PACKED erb_dops {
uint32_t time;
uint16_t gDOP;
uint16_t pDOP;
uint16_t vDOP;
uint16_t hDOP;
uint32_t time; ///< GPS time of week of the navigation epoch [ms]
uint16_t gDOP; ///< Geometric DOP
uint16_t pDOP; ///< Position DOP
uint16_t vDOP; ///< Vertical DOP
uint16_t hDOP; ///< Horizontal DOP
};
struct PACKED erb_vel {
uint32_t time;
int32_t vel_north;
int32_t vel_east;
int32_t vel_down;
uint32_t speed_2d;
int32_t heading_2d;
uint32_t speed_accuracy;
uint32_t time; ///< GPS time of week of the navigation epoch [ms]
int32_t vel_north; ///< North velocity component [cm/s]
int32_t vel_east; ///< East velocity component [cm/s]
int32_t vel_down; ///< Down velocity component [cm/s]
uint32_t speed_2d; ///< Ground speed (2-D) [cm/s]
int32_t heading_2d; ///< Heading of motion 2-D [1e5 deg]
uint32_t speed_accuracy; ///< Speed accuracy Estimate [cm/s]
};
// Receive buffer

View File

@ -114,26 +114,26 @@ private:
struct PACKED bestpos
{
uint32_t solstat;
uint32_t postype;
double lat;
double lng;
double hgt;
float undulation;
uint32_t datumid;
float latsdev;
float lngsdev;
float hgtsdev;
uint32_t solstat; ///< Solution status
uint32_t postype; ///< Position type
double lat; ///< latitude (deg)
double lng; ///< longitude (deg)
double hgt; ///< height above mean sea level (m)
float undulation; ///< relationship between the geoid and the ellipsoid (m)
uint32_t datumid; ///< datum id number
float latsdev; ///< latitude standard deviation (m)
float lngsdev; ///< longitude standard deviation (m)
float hgtsdev; ///< height standard deviation (m)
// 4 bytes
uint8_t stnid[4];
float diffage;
float sol_age;
uint8_t svstracked;
uint8_t svsused;
uint8_t svsl1;
uint8_t svsmultfreq;
uint8_t resv;
uint8_t extsolstat;
uint8_t stnid[4]; ///< base station id
float diffage; ///< differential position age (sec)
float sol_age; ///< solution age (sec)
uint8_t svstracked; ///< number of satellites tracked
uint8_t svsused; ///< number of satellites used in solution
uint8_t svsl1; ///< number of GPS plus GLONASS L1 satellites used in solution
uint8_t svsmultfreq; ///< number of GPS plus GLONASS L2 satellites used in solution
uint8_t resv; ///< reserved
uint8_t extsolstat; ///< extended solution status - OEMV and greater only
uint8_t galbeisigmask;
uint8_t gpsglosigmask;
};

View File

@ -309,7 +309,7 @@ AP_GPS_SBP2::_attempt_state_update()
state.vertical_accuracy = (float) last_pos_llh.v_accuracy * 1.0e-3f;
//
// Set flags appropriartely
// Set flags appropriately
//
state.have_vertical_velocity = true;
state.have_speed_accuracy = !is_zero(state.speed_accuracy);