AP_GPS: spell in comments

This commit is contained in:
Dr.-Ing. Amilcar Do Carmo Lucas 2017-05-02 16:52:05 +02:00 committed by Randy Mackay
parent 23b7f1e645
commit 1691a39b36

View File

@ -28,7 +28,7 @@
than 1 then redundant sensors may be available than 1 then redundant sensors may be available
*/ */
#define GPS_MAX_RECEIVERS 2 // maximum number of physical GPS sensors allowed - does not include virtual GPS created by blending receiver data #define GPS_MAX_RECEIVERS 2 // maximum number of physical GPS sensors allowed - does not include virtual GPS created by blending receiver data
#define GPS_MAX_INSTANCES (GPS_MAX_RECEIVERS + 1) // maximumum number of GPs instances including the 'virtual' GPS created by blending receiver data #define GPS_MAX_INSTANCES (GPS_MAX_RECEIVERS + 1) // maximum number of GPs instances including the 'virtual' GPS created by blending receiver data
#define GPS_BLENDED_INSTANCE GPS_MAX_RECEIVERS // the virtual blended GPS is always the highest instance (2) #define GPS_BLENDED_INSTANCE GPS_MAX_RECEIVERS // the virtual blended GPS is always the highest instance (2)
#define GPS_RTK_INJECT_TO_ALL 127 #define GPS_RTK_INJECT_TO_ALL 127
#define GPS_MAX_RATE_MS 200 // maximum value of rate_ms (i.e. slowest update rate) is 5hz or 200ms #define GPS_MAX_RATE_MS 200 // maximum value of rate_ms (i.e. slowest update rate) is 5hz or 200ms
@ -132,14 +132,14 @@ public:
uint16_t hdop; ///< horizontal dilution of precision in cm uint16_t hdop; ///< horizontal dilution of precision in cm
uint16_t vdop; ///< vertical dilution of precision in cm uint16_t vdop; ///< vertical dilution of precision in cm
uint8_t num_sats; ///< Number of visible satellites uint8_t num_sats; ///< Number of visible satellites
Vector3f velocity; ///< 3D velocitiy in m/s, in NED format Vector3f velocity; ///< 3D velocity in m/s, in NED format
float speed_accuracy; ///< 3D velocity accuracy estimate in m/s float speed_accuracy; ///< 3D velocity accuracy estimate in m/s
float horizontal_accuracy; ///< horizontal accuracy estimate in m float horizontal_accuracy; ///< horizontal accuracy estimate in m
float vertical_accuracy; ///< vertical accuracy estimate in m float vertical_accuracy; ///< vertical accuracy estimate in m
bool have_vertical_velocity:1; ///< does GPS give vertical velocity? Set to true only once available. 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_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. bool have_horizontal_accuracy:1; ///< does GPS give horizontal position accuracy? Set to true only once available.
bool have_vertical_accuracy:1; ///< does GPS give vertical position accuract? Set to true only once available. bool have_vertical_accuracy:1; ///< does GPS give vertical position accuracy? Set to true only once available.
uint32_t last_gps_time_ms; ///< the system time we got the last GPS timestamp, milliseconds uint32_t last_gps_time_ms; ///< the system time we got the last GPS timestamp, milliseconds
}; };