Browse Source

一些消息提示翻译

zr-sdk-4.3.1
nagezeng 3 years ago
parent
commit
09c1202146
  1. 3
      ArduCopter/GCS_Mavlink.cpp
  2. 6
      libraries/AP_Arming/AP_Arming.cpp
  3. 20
      libraries/AP_GPS/AP_GPS_UBLOX.cpp
  4. 3
      libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp
  5. 2
      libraries/AP_NavEKF2/AP_NavEKF2_MagFusion.cpp
  6. 3
      libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp
  7. 29
      libraries/AP_NavEKF2/AP_NavEKF2_VehicleStatus.cpp
  8. 2
      libraries/AP_NavEKF3/AP_NavEKF3_MagFusion.cpp
  9. 3
      libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp

3
ArduCopter/GCS_Mavlink.cpp

@ -1316,7 +1316,8 @@ void Copter::mavlink_delay_cb() @@ -1316,7 +1316,8 @@ void Copter::mavlink_delay_cb()
}
if (tnow - last_5s > 5000) {
last_5s = tnow;
gcs().send_text(MAV_SEVERITY_INFO, "Initialising APM");
// gcs().send_text(MAV_SEVERITY_INFO, "Initialising APM");
gcs().send_text(MAV_SEVERITY_INFO, "系统初始化中···");
}
logger.EnableWrites(true);

6
libraries/AP_Arming/AP_Arming.cpp

@ -175,7 +175,8 @@ void AP_Arming::check_failed(const enum AP_Arming::ArmingChecks check, bool repo @@ -175,7 +175,8 @@ void AP_Arming::check_failed(const enum AP_Arming::ArmingChecks check, bool repo
return;
}
char taggedfmt[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];
hal.util->snprintf(taggedfmt, sizeof(taggedfmt), "PreArm: %s", fmt);
// hal.util->snprintf(taggedfmt, sizeof(taggedfmt), "PreArm: %s", fmt);
hal.util->snprintf(taggedfmt, sizeof(taggedfmt), "自检中: %s", fmt);
MAV_SEVERITY severity = check_severity(check);
va_list arg_list;
va_start(arg_list, fmt);
@ -189,7 +190,8 @@ void AP_Arming::check_failed(bool report, const char *fmt, ...) const @@ -189,7 +190,8 @@ void AP_Arming::check_failed(bool report, const char *fmt, ...) const
return;
}
char taggedfmt[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];
hal.util->snprintf(taggedfmt, sizeof(taggedfmt), "PreArm: %s", fmt);
// hal.util->snprintf(taggedfmt, sizeof(taggedfmt), "PreArm: %s", fmt);
hal.util->snprintf(taggedfmt, sizeof(taggedfmt), "自检中: %s", fmt);
va_list arg_list;
va_start(arg_list, fmt);
gcs().send_textv(MAV_SEVERITY_CRITICAL, taggedfmt, arg_list);

20
libraries/AP_GPS/AP_GPS_UBLOX.cpp

@ -948,13 +948,13 @@ AP_GPS_UBLOX::_parse_gps(void) @@ -948,13 +948,13 @@ AP_GPS_UBLOX::_parse_gps(void)
break;
case MSG_MON_VER:
_have_version = true;
strncpy(_version.hwVersion, _buffer.mon_ver.hwVersion, sizeof(_version.hwVersion));
strncpy(_version.swVersion, _buffer.mon_ver.swVersion, sizeof(_version.swVersion));
GCS_SEND_TEXT(MAV_SEVERITY_INFO,
"u-blox %d HW: %s SW: %s",
state.instance + 1,
_version.hwVersion,
_version.swVersion);
// strncpy(_version.hwVersion, _buffer.mon_ver.hwVersion, sizeof(_version.hwVersion));
// strncpy(_version.swVersion, _buffer.mon_ver.swVersion, sizeof(_version.swVersion));
// GCS_SEND_TEXT(MAV_SEVERITY_INFO,
// "u-blox %d HW: %s SW: %s",
// state.instance + 1,
// _version.hwVersion,
// _version.swVersion);
// check for F9. The F9 does not respond to SVINFO, so we need to use MON_VER
// for hardware generation
if (strncmp(_version.hwVersion, "00190000", 8) == 0) {
@ -1453,9 +1453,9 @@ AP_GPS_UBLOX::_save_cfg() @@ -1453,9 +1453,9 @@ AP_GPS_UBLOX::_save_cfg()
_send_message(CLASS_CFG, MSG_CFG_CFG, &save_cfg, sizeof(save_cfg));
_last_cfg_sent_time = AP_HAL::millis();
_num_cfg_save_tries++;
GCS_SEND_TEXT(MAV_SEVERITY_INFO,
"GPS: u-blox %d saving config",
state.instance + 1);
// GCS_SEND_TEXT(MAV_SEVERITY_INFO,
// "GPS: u-blox %d saving config",
// state.instance + 1);
}
/*

3
libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp

@ -348,7 +348,8 @@ void NavEKF2_core::checkAttitudeAlignmentStatus() @@ -348,7 +348,8 @@ void NavEKF2_core::checkAttitudeAlignmentStatus()
tiltErrFilt = alpha*temp + (1.0f-alpha)*tiltErrFilt;
if (tiltErrFilt < 0.005f && !tiltAlignComplete) {
tiltAlignComplete = true;
gcs().send_text(MAV_SEVERITY_INFO, "EKF2 IMU%u tilt alignment complete",(unsigned)imu_index);
// gcs().send_text(MAV_SEVERITY_INFO, "EKF2 IMU%u tilt alignment complete",(unsigned)imu_index);
gcs().send_text(MAV_SEVERITY_INFO, "EKF2 IMU%u收敛完成",(unsigned)imu_index);
}
// submit yaw and magnetic field reset requests depending on whether we have compass data

2
libraries/AP_NavEKF2/AP_NavEKF2_MagFusion.cpp

@ -142,7 +142,7 @@ void NavEKF2_core::controlMagYawReset() @@ -142,7 +142,7 @@ void NavEKF2_core::controlMagYawReset()
// send initial alignment status to console
if (!yawAlignComplete) {
gcs().send_text(MAV_SEVERITY_INFO, "EKF2 IMU%u初始偏航校准完成",(unsigned)imu_index);//EKF2 IMU%u initial yaw alignment complete
gcs().send_text(MAV_SEVERITY_INFO, "EKF2 IMU%u偏航校准完成",(unsigned)imu_index);//EKF2 IMU%u initial yaw alignment complete
}
// send in-flight yaw alignment status to console

3
libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp

@ -603,7 +603,8 @@ void NavEKF2_core::readGpsData() @@ -603,7 +603,8 @@ void NavEKF2_core::readGpsData()
} else {
// report GPS fix status
gpsCheckStatus.bad_fix = true;
hal.util->snprintf(prearm_fail_string, sizeof(prearm_fail_string), "Waiting for 3D fix");
// hal.util->snprintf(prearm_fail_string, sizeof(prearm_fail_string), "Waiting for 3D fix");
hal.util->snprintf(prearm_fail_string, sizeof(prearm_fail_string), "等待卫星定位");
}
}
}

29
libraries/AP_NavEKF2/AP_NavEKF2_VehicleStatus.cpp

@ -79,7 +79,8 @@ void NavEKF2_core::calcGpsGoodToAlign(void) @@ -79,7 +79,8 @@ void NavEKF2_core::calcGpsGoodToAlign(void)
if (gpsDriftFail) {
hal.util->snprintf(prearm_fail_string,
sizeof(prearm_fail_string),
"GPS drift %.1fm (needs %.1f)", (double)gpsDriftNE, (double)(3.0f*checkScaler));
"GNSS定位飘移 %.1fm (需小于 %.1f)", (double)gpsDriftNE, (double)(3.0f*checkScaler));
// "GPS drift %.1fm (needs %.1f)", (double)gpsDriftNE, (double)(3.0f*checkScaler));
gpsCheckStatus.bad_horiz_drift = true;
} else {
gpsCheckStatus.bad_horiz_drift = false;
@ -110,7 +111,8 @@ void NavEKF2_core::calcGpsGoodToAlign(void) @@ -110,7 +111,8 @@ void NavEKF2_core::calcGpsGoodToAlign(void)
if (gpsVertVelFail) {
hal.util->snprintf(prearm_fail_string,
sizeof(prearm_fail_string),
"GPS vertical speed %.2fm/s (needs %.2f)", (double)fabsf(gpsVertVelFilt), (double)(0.3f*checkScaler));
"GNSS垂直速度过大 %.2fm/s (需小于 %.2f)", (double)fabsf(gpsVertVelFilt), (double)(0.3f*checkScaler));
// "GPS vertical speed %.2fm/s (needs %.2f)", (double)fabsf(gpsVertVelFilt), (double)(0.3f*checkScaler));
gpsCheckStatus.bad_vert_vel = true;
} else {
gpsCheckStatus.bad_vert_vel = false;
@ -131,7 +133,8 @@ void NavEKF2_core::calcGpsGoodToAlign(void) @@ -131,7 +133,8 @@ void NavEKF2_core::calcGpsGoodToAlign(void)
if (gpsHorizVelFail) {
hal.util->snprintf(prearm_fail_string,
sizeof(prearm_fail_string),
"GPS horizontal speed %.2fm/s (needs %.2f)", (double)gpsDriftNE, (double)(0.3f*checkScaler));
"GNSS水平速度过大 %.2fm/s (需小于 %.2f)", (double)gpsDriftNE, (double)(0.3f*checkScaler));
// "GPS horizontal speed %.2fm/s (needs %.2f)", (double)gpsDriftNE, (double)(0.3f*checkScaler));
gpsCheckStatus.bad_horiz_vel = true;
} else {
gpsCheckStatus.bad_horiz_vel = false;
@ -150,7 +153,8 @@ void NavEKF2_core::calcGpsGoodToAlign(void) @@ -150,7 +153,8 @@ void NavEKF2_core::calcGpsGoodToAlign(void)
if (hAccFail) {
hal.util->snprintf(prearm_fail_string,
sizeof(prearm_fail_string),
"GPS horiz error %.1fm (needs %.1f)", (double)hAcc, (double)(5.0f*checkScaler));
"GNSS水平定位差值过大 %.1fm (需小于 %.1f)", (double)hAcc, (double)(5.0f*checkScaler));
// "GPS horiz error %.1fm (needs %.1f)", (double)hAcc, (double)(5.0f*checkScaler));
gpsCheckStatus.bad_hAcc = true;
} else {
gpsCheckStatus.bad_hAcc = false;
@ -166,7 +170,8 @@ void NavEKF2_core::calcGpsGoodToAlign(void) @@ -166,7 +170,8 @@ void NavEKF2_core::calcGpsGoodToAlign(void)
if (vAccFail) {
hal.util->snprintf(prearm_fail_string,
sizeof(prearm_fail_string),
"GPS vert error %.1fm (needs < %.1f)", (double)vAcc, (double)(7.5f * checkScaler));
"GNSS垂直定位差值过大 %.1fm (需小于 < %.1f)", (double)vAcc, (double)(7.5f * checkScaler));
// "GPS vert error %.1fm (needs < %.1f)", (double)vAcc, (double)(7.5f * checkScaler));
gpsCheckStatus.bad_vAcc = true;
} else {
gpsCheckStatus.bad_vAcc = false;
@ -179,7 +184,8 @@ void NavEKF2_core::calcGpsGoodToAlign(void) @@ -179,7 +184,8 @@ void NavEKF2_core::calcGpsGoodToAlign(void)
if (gpsSpdAccFail) {
hal.util->snprintf(prearm_fail_string,
sizeof(prearm_fail_string),
"GPS speed error %.1f (needs < %.1f)", (double)gpsSpdAccuracy, (double)(1.0f*checkScaler));
"GNSS速度差值过大 %.1f (需小于 < %.1f)", (double)gpsSpdAccuracy, (double)(1.0f*checkScaler));
// "GPS speed error %.1f (needs < %.1f)", (double)gpsSpdAccuracy, (double)(1.0f*checkScaler));
gpsCheckStatus.bad_sAcc = true;
} else {
gpsCheckStatus.bad_sAcc = false;
@ -191,19 +197,21 @@ void NavEKF2_core::calcGpsGoodToAlign(void) @@ -191,19 +197,21 @@ void NavEKF2_core::calcGpsGoodToAlign(void)
// Report check result as a text string and bitmask
if (hdopFail) {
hal.util->snprintf(prearm_fail_string, sizeof(prearm_fail_string),
"GPS HDOP %.1f (needs 2.5)", (double)(0.01f * gps.get_hdop()));
"GNSS HDOP %.1f (需小于 2.5)", (double)(0.01f * gps.get_hdop()));
// "GPS HDOP %.1f (needs 2.5)", (double)(0.01f * gps.get_hdop()));
gpsCheckStatus.bad_hdop = true;
} else {
gpsCheckStatus.bad_hdop = false;
}
// fail if not enough sats
bool numSatsFail = (gps.num_sats() < 6) && (frontend->_gpsCheck & MASK_GPS_NSATS);
bool numSatsFail = (gps.num_sats() < 9) && (frontend->_gpsCheck & MASK_GPS_NSATS);
// Report check result as a text string and bitmask
if (numSatsFail) {
hal.util->snprintf(prearm_fail_string, sizeof(prearm_fail_string),
"GPS numsats %u (needs 6)", gps.num_sats());
"GNSS卫星数 %u (需大于 9)", gps.num_sats());
// "GPS numsats %u (needs 6)", gps.num_sats());
gpsCheckStatus.bad_sats = true;
} else {
gpsCheckStatus.bad_sats = false;
@ -232,7 +240,8 @@ void NavEKF2_core::calcGpsGoodToAlign(void) @@ -232,7 +240,8 @@ void NavEKF2_core::calcGpsGoodToAlign(void)
// assume failed first time through and notify user checks have started
if (lastGpsVelFail_ms == 0) {
hal.util->snprintf(prearm_fail_string, sizeof(prearm_fail_string), "EKF starting GPS checks");
hal.util->snprintf(prearm_fail_string, sizeof(prearm_fail_string), "EKF开始GNSS检查");
// hal.util->snprintf(prearm_fail_string, sizeof(prearm_fail_string), "EKF starting GPS checks");
lastGpsVelFail_ms = imuSampleTime_ms;
}

2
libraries/AP_NavEKF3/AP_NavEKF3_MagFusion.cpp

@ -117,7 +117,7 @@ void NavEKF3_core::controlMagYawReset() @@ -117,7 +117,7 @@ void NavEKF3_core::controlMagYawReset()
// send initial alignment status to console
if (!yawAlignComplete) {
gcs().send_text(MAV_SEVERITY_INFO, "EKF3 IMU%u 初始偏航校准完成",(unsigned)imu_index); //EKF3 IMU%u initial yaw alignment complete
gcs().send_text(MAV_SEVERITY_INFO, "EKF3 IMU%u偏航校准完成",(unsigned)imu_index); //EKF3 IMU%u initial yaw alignment complete
}
// send in-flight yaw alignment status to console

3
libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp

@ -646,7 +646,8 @@ void NavEKF3_core::readGpsData() @@ -646,7 +646,8 @@ void NavEKF3_core::readGpsData()
} else {
// report GPS fix status
gpsCheckStatus.bad_fix = true;
hal.util->snprintf(prearm_fail_string, sizeof(prearm_fail_string), "Waiting for 3D fix");
// hal.util->snprintf(prearm_fail_string, sizeof(prearm_fail_string), "Waiting for 3D fix");
hal.util->snprintf(prearm_fail_string, sizeof(prearm_fail_string), "等待卫星定位");
}
}
}

Loading…
Cancel
Save