mirror of https://github.com/ArduPilot/ardupilot
AP_GPS: Fix some typos
Fixed some typos found in the code.
This commit is contained in:
parent
3acd0b3817
commit
3a7e939a6c
|
@ -1482,7 +1482,7 @@ void AP_GPS::send_mavlink_gps_raw(mavlink_channel_t chan)
|
|||
ground_speed(0)*100, // cm/s
|
||||
ground_course(0)*100, // 1/100 degrees,
|
||||
num_sats(0),
|
||||
height_elipsoid_mm, // Elipsoid height in mm
|
||||
height_elipsoid_mm, // Ellipsoid height in mm
|
||||
hacc * 1000, // one-sigma standard deviation in mm
|
||||
vacc * 1000, // one-sigma standard deviation in mm
|
||||
sacc * 1000, // one-sigma standard deviation in mm/s
|
||||
|
@ -1525,7 +1525,7 @@ void AP_GPS::send_mavlink_gps2_raw(mavlink_channel_t chan)
|
|||
state[1].rtk_num_sats,
|
||||
state[1].rtk_age_ms,
|
||||
gps_yaw_cdeg(1),
|
||||
height_elipsoid_mm, // Elipsoid height in mm
|
||||
height_elipsoid_mm, // Ellipsoid height in mm
|
||||
hacc * 1000, // one-sigma standard deviation in mm
|
||||
vacc * 1000, // one-sigma standard deviation in mm
|
||||
sacc * 1000, // one-sigma standard deviation in mm/s
|
||||
|
@ -1703,7 +1703,7 @@ void AP_GPS::Write_AP_Logger_Log_Startup_messages()
|
|||
*/
|
||||
bool AP_GPS::get_lag(uint8_t instance, float &lag_sec) const
|
||||
{
|
||||
// always enusre a lag is provided
|
||||
// always ensure a lag is provided
|
||||
lag_sec = 0.1f;
|
||||
|
||||
if (instance >= GPS_MAX_INSTANCES) {
|
||||
|
|
|
@ -800,7 +800,7 @@ void AP_GPS_DroneCAN::inject_data(const uint8_t *data, uint16_t len)
|
|||
{
|
||||
// we only handle this if we are the first DroneCAN GPS or we are
|
||||
// using a different uavcan instance than the first GPS, as we
|
||||
// send the data as broadcast on all DroneCAN devive ports and we
|
||||
// send the data as broadcast on all DroneCAN device ports and we
|
||||
// don't want to send duplicates
|
||||
const uint32_t now_ms = AP_HAL::millis();
|
||||
if (_detected_module == 0 ||
|
||||
|
|
|
@ -629,7 +629,7 @@ bool AP_GPS_NMEA::_term_complete()
|
|||
//
|
||||
case _GPS_SENTENCE_RMC + 7: // Speed (GPRMC)
|
||||
case _GPS_SENTENCE_VTG + 5: // Speed (VTG)
|
||||
_new_speed = (_parse_decimal_100(_term) * 514) / 1000; // knots-> m/sec, approximiates * 0.514
|
||||
_new_speed = (_parse_decimal_100(_term) * 514) / 1000; // knots-> m/sec, approximates * 0.514
|
||||
break;
|
||||
case _GPS_SENTENCE_HDT + 1: // Course (HDT)
|
||||
_new_gps_yaw = _parse_decimal_100(_term);
|
||||
|
|
|
@ -1102,7 +1102,7 @@ AP_GPS_UBLOX::_parse_gps(void)
|
|||
}
|
||||
if(GNSS_GALILEO ==_buffer.gnss.configBlock[i].gnssId) {
|
||||
_buffer.gnss.configBlock[i].resTrkCh = (_buffer.gnss.numTrkChHw - 3) / (gnssCount * 2);
|
||||
_buffer.gnss.configBlock[i].maxTrkCh = 8; //Per the M8 receiver description UBX-13003221 - R16, 4.1.1.3 it is not recommended to set the number of galileo channels higher then eigh
|
||||
_buffer.gnss.configBlock[i].maxTrkCh = 8; //Per the M8 receiver description UBX-13003221 - R16, 4.1.1.3 it is not recommended to set the number of galileo channels higher then eight
|
||||
}
|
||||
}
|
||||
_buffer.gnss.configBlock[i].flags = _buffer.gnss.configBlock[i].flags | 0x00000001;
|
||||
|
|
|
@ -350,14 +350,14 @@ bool AP_GPS_Backend::calculate_moving_base_yaw(AP_GPS::GPS_State &interim_state,
|
|||
const float min_dist = MIN(offset_dist, reported_distance);
|
||||
|
||||
if (offset_dist < minimum_antenna_seperation) {
|
||||
// offsets have to be sufficently large to get a meaningful angle off of them
|
||||
// offsets have to be sufficiently large to get a meaningful angle off of them
|
||||
Debug("Insufficent antenna offset (%f, %f, %f)", (double)offset.x, (double)offset.y, (double)offset.z);
|
||||
goto bad_yaw;
|
||||
}
|
||||
|
||||
if (reported_distance < minimum_antenna_seperation) {
|
||||
// if the reported distance is less then the minimum seperation it's not sufficently robust
|
||||
Debug("Reported baseline distance (%f) was less then the minimum antenna seperation (%f)",
|
||||
// if the reported distance is less then the minimum separation it's not sufficiently robust
|
||||
Debug("Reported baseline distance (%f) was less then the minimum antenna separation (%f)",
|
||||
(double)reported_distance, (double)minimum_antenna_seperation);
|
||||
goto bad_yaw;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue