Browse Source

Merge branch 'v4.0.4-dev-rc2-chinese' into v4.0.4-dev-rc3

master
zbr3550 5 years ago
parent
commit
9bdf1bd0f2
  1. 67
      ArduCopter/AP_Arming.cpp
  2. 2
      ArduCopter/GCS_Mavlink.cpp
  3. 12
      ArduCopter/compassmot.cpp
  4. 4
      ArduCopter/crash_check.cpp
  5. 6
      ArduCopter/ekf_check.cpp
  6. 2
      ArduCopter/esc_calibration.cpp
  7. 6
      ArduCopter/events.cpp
  8. 10
      ArduCopter/mode.cpp
  9. 2
      ArduCopter/mode_auto.cpp
  10. 2
      ArduCopter/mode_land.cpp
  11. 2
      ArduCopter/mode_rtl.cpp
  12. 4
      ArduPlane/AP_Arming.cpp
  13. 90
      libraries/AP_Arming/AP_Arming.cpp
  14. 6
      libraries/AP_BattMonitor/AP_BattMonitor.cpp
  15. 42
      libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp
  16. 2
      libraries/AP_Compass/AP_Compass_Calibration.cpp
  17. 6
      libraries/AP_Compass/CompassCalibrator.cpp
  18. 4
      libraries/AP_Landing/AP_Landing.cpp
  19. 2
      libraries/AP_Logger/AP_Logger_File.cpp
  20. 4
      libraries/AP_Mission/AP_Mission.cpp
  21. 2
      libraries/AP_Motors/AP_MotorsHeli_Quad.cpp
  22. 2
      libraries/AP_Motors/AP_MotorsTri.cpp
  23. 2
      libraries/AP_Motors/AP_Motors_Class.cpp
  24. 4
      libraries/AP_NavEKF2/AP_NavEKF2.cpp
  25. 2
      libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp
  26. 6
      libraries/AP_NavEKF2/AP_NavEKF2_MagFusion.cpp
  27. 2
      libraries/AP_NavEKF2/AP_NavEKF2_core.cpp
  28. 4
      libraries/AP_NavEKF3/AP_NavEKF3.cpp
  29. 6
      libraries/AP_NavEKF3/AP_NavEKF3_MagFusion.cpp
  30. 2
      libraries/AP_NavEKF3/AP_NavEKF3_VehicleStatus.cpp
  31. 6
      libraries/AP_NavEKF3/AP_NavEKF3_core.cpp
  32. 8
      libraries/AP_Scripting/AP_Scripting.cpp
  33. 2
      libraries/AP_Terrain/AP_Terrain.cpp
  34. 2
      libraries/AP_UAVCAN/AP_UAVCAN_Server.cpp
  35. 2
      libraries/GCS_MAVLink/GCS_Param.cpp
  36. 2
      libraries/GCS_MAVLink/GCS_Rally.cpp
  37. 4
      libraries/GCS_MAVLink/GCS_Signing.cpp
  38. 4
      libraries/GCS_MAVLink/MissionItemProtocol.cpp
  39. 2
      libraries/GCS_MAVLink/MissionItemProtocol_Waypoints.cpp
  40. 2
      libraries/RC_Channel/RC_Channel.cpp

67
ArduCopter/AP_Arming.cpp

@ -79,7 +79,7 @@ bool AP_Arming_Copter::barometer_checks(bool display_failure) @@ -79,7 +79,7 @@ bool AP_Arming_Copter::barometer_checks(bool display_failure)
bool using_baro_ref = (!filt_status.flags.pred_horiz_pos_rel && filt_status.flags.pred_horiz_pos_abs);
if (using_baro_ref) {
if (fabsf(copter.inertial_nav.get_altitude() - copter.baro_alt) > PREARM_MAX_ALT_DISPARITY_CM) {
check_failed(ARMING_CHECK_BARO, display_failure, "Altitude disparity");
check_failed(ARMING_CHECK_BARO, display_failure, "高度差异");//Altitude disparity
ret = false;
}
}
@ -95,7 +95,7 @@ bool AP_Arming_Copter::compass_checks(bool display_failure) @@ -95,7 +95,7 @@ bool AP_Arming_Copter::compass_checks(bool display_failure)
// check compass offsets have been set. AP_Arming only checks
// this if learning is off; Copter *always* checks.
if (!AP::compass().configured()) {
check_failed(ARMING_CHECK_COMPASS, display_failure, "Compass not calibrated");
check_failed(ARMING_CHECK_COMPASS, display_failure, "指南针未校准");//Compass not calibrated
ret = false;
}
}
@ -111,7 +111,7 @@ bool AP_Arming_Copter::ins_checks(bool display_failure) @@ -111,7 +111,7 @@ bool AP_Arming_Copter::ins_checks(bool display_failure)
// get ekf attitude (if bad, it's usually the gyro biases)
if (!pre_arm_ekf_attitude_check()) {
check_failed(ARMING_CHECK_INS, display_failure, "EKF attitude is bad");
check_failed(ARMING_CHECK_INS, display_failure, "EKF姿态不好");//EKF attitude is bad
ret = false;
}
}
@ -128,7 +128,7 @@ bool AP_Arming_Copter::board_voltage_checks(bool display_failure) @@ -128,7 +128,7 @@ bool AP_Arming_Copter::board_voltage_checks(bool display_failure)
// check battery voltage
if ((checks_to_perform == ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_VOLTAGE)) {
if (copter.battery.has_failsafed()) {
check_failed(ARMING_CHECK_VOLTAGE, display_failure, "Battery failsafe");
check_failed(ARMING_CHECK_VOLTAGE, display_failure, "电池故障保护"); //
return false;
}
@ -148,7 +148,7 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure) @@ -148,7 +148,7 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure)
// ensure all rc channels have different functions
if (rc().duplicate_options_exist()) {
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Duplicate Aux Switch Options");
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "辅助开关选项重复");//Duplicate Aux Switch Options
return false;
}
@ -156,14 +156,14 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure) @@ -156,14 +156,14 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure)
if (copter.g.failsafe_throttle) {
// check throttle min is above throttle failsafe trigger and that the trigger is above ppm encoder's loss-of-signal value of 900
if (copter.channel_throttle->get_radio_min() <= copter.g.failsafe_throttle_value+10 || copter.g.failsafe_throttle_value < 910) {
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Check FS_THR_VALUE");
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "检查参数 FS_THR_VALUE");//Check FS_THR_VALUE
return false;
}
}
// lean angle parameter check
if (copter.aparm.angle_max < 1000 || copter.aparm.angle_max > 8000) {
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Check ANGLE_MAX");
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "检查参数 ANGLE_MAX");//Check ANGLE_MAX
return false;
}
@ -177,7 +177,7 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure) @@ -177,7 +177,7 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure)
// pilot-speed-up parameter check
if (copter.g.pilot_speed_up <= 0) {
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Check PILOT_SPEED_UP");
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "检查参数 PILOT_SPEED_UP");//Check PILOT_SPEED_UP
return false;
}
@ -185,7 +185,7 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure) @@ -185,7 +185,7 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure)
if (copter.g2.frame_class.get() != AP_Motors::MOTOR_FRAME_HELI_QUAD &&
copter.g2.frame_class.get() != AP_Motors::MOTOR_FRAME_HELI_DUAL &&
copter.g2.frame_class.get() != AP_Motors::MOTOR_FRAME_HELI) {
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Invalid Heli FRAME_CLASS");
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Invalid Heli FRAME_CLASS");
return false;
}
@ -218,7 +218,7 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure) @@ -218,7 +218,7 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure)
if (copter.g2.frame_class.get() == AP_Motors::MOTOR_FRAME_HELI_QUAD ||
copter.g2.frame_class.get() == AP_Motors::MOTOR_FRAME_HELI_DUAL ||
copter.g2.frame_class.get() == AP_Motors::MOTOR_FRAME_HELI) {
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Invalid MultiCopter FRAME_CLASS");
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Invalid MultiCopter FRAME_CLASS");
return false;
}
#endif // HELI_FRAME
@ -293,9 +293,9 @@ bool AP_Arming_Copter::pilot_throttle_checks(bool display_failure) @@ -293,9 +293,9 @@ bool AP_Arming_Copter::pilot_throttle_checks(bool display_failure)
#if FRAME_CONFIG == HELI_FRAME
const char *failmsg = "Collective below Failsafe";
#else
const char *failmsg = "Throttle below Failsafe";
const char *failmsg = "油门低于故障安全值";//Throttle below Failsafe
#endif
check_failed(ARMING_CHECK_RC, display_failure, "%s", failmsg);
check_failed(ARMING_CHECK_RC, display_failure, "%s", failmsg);
return false;
}
}
@ -312,7 +312,7 @@ bool AP_Arming_Copter::oa_checks(bool display_failure) @@ -312,7 +312,7 @@ bool AP_Arming_Copter::oa_checks(bool display_failure)
}
// display failure
if (strlen(failure_msg) == 0) {
check_failed(display_failure, "%s", "Check Object Avoidance");
check_failed(display_failure, "%s", "Check Object Avoidance"); //Check Object Avoidance
} else {
check_failed(display_failure, "%s", failure_msg);
}
@ -370,7 +370,7 @@ bool AP_Arming_Copter::gps_checks(bool display_failure) @@ -370,7 +370,7 @@ bool AP_Arming_Copter::gps_checks(bool display_failure)
// warn about hdop separately - to prevent user confusion with no gps lock
if (copter.gps.get_hdop() > copter.g.gps_hdop_good) {
check_failed(ARMING_CHECK_GPS, display_failure, "High GPS HDOP %d (need %d)",copter.gps.get_hdop(),copter.g.gps_hdop_good);
check_failed(ARMING_CHECK_GPS, display_failure, " GPS HDOP过高%d(需要%d)",copter.gps.get_hdop(),copter.g.gps_hdop_good); //High GPS HDOP
AP_Notify::flags.pre_arm_gps_check = false;
return false;
}
@ -408,7 +408,7 @@ bool AP_Arming_Copter::pre_arm_terrain_check(bool display_failure) @@ -408,7 +408,7 @@ bool AP_Arming_Copter::pre_arm_terrain_check(bool display_failure)
// To-Do: modify RTL return path to fly at or above the RTL_ALT and remove this check
if (copter.rangefinder_state.enabled && (copter.g.rtl_altitude > copter.rangefinder.max_distance_cm_orient(ROTATION_PITCH_270))) {
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "RTL_ALT above rangefinder max range");
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "返回高度参数大于测距传感器最大范围");//RTL_ALT above rangefinder max range
return false;
}
@ -417,7 +417,7 @@ bool AP_Arming_Copter::pre_arm_terrain_check(bool display_failure) @@ -417,7 +417,7 @@ bool AP_Arming_Copter::pre_arm_terrain_check(bool display_failure)
copter.terrain.get_statistics(terr_pending, terr_loaded);
bool have_all_data = (terr_pending <= 0);
if (!have_all_data) {
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Waiting for Terrain data");
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "等待地形数据");//Waiting for Terrain data
}
return have_all_data;
#else
@ -445,7 +445,7 @@ bool AP_Arming_Copter::proximity_checks(bool display_failure) const @@ -445,7 +445,7 @@ bool AP_Arming_Copter::proximity_checks(bool display_failure) const
if (copter.avoid.proximity_avoidance_enabled() && copter.g2.proximity.get_closest_object(angle_deg, distance)) {
// display error if something is within 60cm
if (distance <= 0.6f) {
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Proximity %d deg, %4.2fm", (int)angle_deg, (double)distance);
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "障碍物过近,距离:%4.2f米",(double)distance);//Proximity %d deg, %4.2fm //(int)angle_deg,
return false;
}
}
@ -514,9 +514,9 @@ bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure) @@ -514,9 +514,9 @@ bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure)
if (reason == nullptr) {
if (!mode_requires_gps && fence_requires_gps) {
// clarify to user why they need GPS in non-GPS flight mode
reason = "Fence enabled, need 3D Fix";
reason = "地理围栏启动,需卫星定位"; //ence enabled, need 3D Fix
} else {
reason = "Need 3D Fix";
reason = "GPS定位中..."; //need 3D Fix
}
}
check_failed(display_failure, "%s", reason);
@ -531,7 +531,7 @@ bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure) @@ -531,7 +531,7 @@ bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure)
nav_filter_status filt_status;
if (ahrs.get_filter_status(filt_status)) {
if (filt_status.flags.gps_glitching) {
check_failed(display_failure, "GPS glitching");
check_failed(display_failure, "GPS数据异常"); //GPS glitching
return false;
}
}
@ -542,13 +542,13 @@ bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure) @@ -542,13 +542,13 @@ bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure)
Vector2f offset;
ahrs.get_variances(vel_variance, pos_variance, hgt_variance, mag_variance, tas_variance, offset);
if (copter.g.fs_ekf_thresh > 0 && mag_variance.length() >= copter.g.fs_ekf_thresh) {
check_failed(display_failure, "EKF compass variance");
check_failed(display_failure, "EKF指南针偏差");//
return false;
}
// check home and EKF origin are not too far
if (copter.far_from_EKF_origin(ahrs.get_home())) {
check_failed(display_failure, "EKF-home variance");
check_failed(display_failure, "EKF-返航点偏差");
return false;
}
@ -571,7 +571,7 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method) @@ -571,7 +571,7 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method)
// always check if inertial nav has started and is ready
if (!ahrs.healthy()) {
check_failed(true, "AHRS not healthy");
check_failed(true, "姿态不健康");//AHRS not healthy
return false;
}
@ -581,7 +581,7 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method) @@ -581,7 +581,7 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method)
const Compass &_compass = AP::compass();
// check compass health
if (!_compass.healthy()) {
check_failed(true, "Compass not healthy");
check_failed(true, "指南针不健康");//Compass not healthy
return false;
}
}
@ -591,7 +591,7 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method) @@ -591,7 +591,7 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method)
// always check if the current mode allows arming
if (!copter.flightmode->allows_arming(method == AP_Arming::Method::MAVLINK)) {
check_failed(true, "Mode not armable");
check_failed(true, "当前模式不能解锁");//Mode not armable
return false;
}
@ -599,7 +599,6 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method) @@ -599,7 +599,6 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method)
if (!motor_checks(true)) {
return false;
}
// if we are using motor interlock switch and it's enabled, fail to arm
// skip check in Throw mode which takes control of the motor interlock
if (copter.ap.using_interlock && copter.ap.motor_interlock_switch) {
@ -613,7 +612,7 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method) @@ -613,7 +612,7 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method)
SRV_Channels::set_emergency_stop(false);
// if we are using motor Estop switch, it must not be in Estop position
} else if (rc().find_channel_for_option(RC_Channel::AUX_FUNC::MOTOR_ESTOP) && SRV_Channels::get_emergency_stop()){
gcs().send_text(MAV_SEVERITY_CRITICAL,"Arm: Motor Emergency Stopped");
gcs().send_text(MAV_SEVERITY_CRITICAL,"Arm:电机紧急停止");//Arm: Motor Emergency Stopped
return false;
}
@ -645,11 +644,11 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method) @@ -645,11 +644,11 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method)
#if FRAME_CONFIG == HELI_FRAME
const char *rc_item = "Collective";
#else
const char *rc_item = "Throttle";
const char *rc_item = "油门"; //Throttle
#endif
// check throttle is not too low - must be above failsafe throttle
if (copter.g.failsafe_throttle != FS_THR_DISABLED && copter.channel_throttle->get_radio_in() < copter.g.failsafe_throttle_value) {
check_failed(ARMING_CHECK_RC, true, "%s below failsafe", rc_item);
check_failed(ARMING_CHECK_RC, true, "%s低于故障保护值", rc_item);//%s below failsafe
return false;
}
@ -657,13 +656,13 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method) @@ -657,13 +656,13 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method)
if (!(method == AP_Arming::Method::MAVLINK && (control_mode == Mode::Number::GUIDED || control_mode == Mode::Number::GUIDED_NOGPS))) {
// above top of deadband is too always high
if (copter.get_pilot_desired_climb_rate(copter.channel_throttle->get_control_in()) > 0.0f) {
check_failed(ARMING_CHECK_RC, true, "%s too high", rc_item);
check_failed(ARMING_CHECK_RC, true, "%s过高", rc_item);//%s too high
return false;
}
// in manual modes throttle must be at zero
#if FRAME_CONFIG != HELI_FRAME
if ((copter.flightmode->has_manual_throttle() || control_mode == Mode::Number::DRIFT) && copter.channel_throttle->get_control_in() > 0) {
check_failed(ARMING_CHECK_RC, true, "%s too high", rc_item);
check_failed(ARMING_CHECK_RC, true, "%s过高", rc_item);//%s too high
return false;
}
#endif
@ -672,7 +671,7 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method) @@ -672,7 +671,7 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method)
// check if safety switch has been pushed
if (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) {
check_failed(true, "Safety Switch");
check_failed(true, "安全开关");//Safety Switch
return false;
}
@ -733,7 +732,7 @@ bool AP_Arming_Copter::arm(const AP_Arming::Method method, const bool do_arming_ @@ -733,7 +732,7 @@ bool AP_Arming_Copter::arm(const AP_Arming::Method method, const bool do_arming_
}
#if HIL_MODE != HIL_MODE_DISABLED || CONFIG_HAL_BOARD == HAL_BOARD_SITL
gcs().send_text(MAV_SEVERITY_INFO, "Arming motors");
gcs().send_text(MAV_SEVERITY_INFO, "解锁电机");//Arming motors
#endif
// Remember Orientation
@ -822,7 +821,7 @@ bool AP_Arming_Copter::disarm() @@ -822,7 +821,7 @@ bool AP_Arming_Copter::disarm()
}
#if HIL_MODE != HIL_MODE_DISABLED || CONFIG_HAL_BOARD == HAL_BOARD_SITL
gcs().send_text(MAV_SEVERITY_INFO, "NOTICE: Disarming motors");
gcs().send_text(MAV_SEVERITY_INFO, "NOTICE: 电机锁定");//NOTICE: Disarming motors
#endif
AP_AHRS_NavEKF &ahrs = AP::ahrs_navekf();

2
ArduCopter/GCS_Mavlink.cpp

@ -569,7 +569,7 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_preflight_reboot(const mavlink_command_lon @@ -569,7 +569,7 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_preflight_reboot(const mavlink_command_lon
{
// reject reboot if user has also specified they want the "Auto" ESC calibration on next reboot
if (copter.g.esc_calibrate == (uint8_t)Copter::ESCCalibrationModes::ESCCAL_AUTO) {
send_text(MAV_SEVERITY_CRITICAL, "Reboot rejected, ESC cal on reboot");
send_text(MAV_SEVERITY_CRITICAL, "重启被拒绝,重启时可进行电调校准");//Reboot rejected, ESC cal on reboot
return MAV_RESULT_FAILED;
}

12
ArduCopter/compassmot.cpp

@ -35,7 +35,7 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan) @@ -35,7 +35,7 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan)
// check compass is enabled
if (!AP::compass().enabled()) {
gcs_chan.send_text(MAV_SEVERITY_CRITICAL, "Compass disabled");
gcs_chan.send_text(MAV_SEVERITY_CRITICAL, "指南针已禁用");//Compass disabled
ap.compass_mot = false;
return MAV_RESULT_TEMPORARILY_REJECTED;
}
@ -44,7 +44,7 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan) @@ -44,7 +44,7 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan)
compass.read();
for (uint8_t i=0; i<compass.get_count(); i++) {
if (!compass.healthy(i)) {
gcs_chan.send_text(MAV_SEVERITY_CRITICAL, "Check compass");
gcs_chan.send_text(MAV_SEVERITY_CRITICAL, "指南针检查");//Check compass
ap.compass_mot = false;
return MAV_RESULT_TEMPORARILY_REJECTED;
}
@ -52,7 +52,7 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan) @@ -52,7 +52,7 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan)
// check if radio is calibrated
if (!arming.rc_calibration_checks(true)) {
gcs_chan.send_text(MAV_SEVERITY_CRITICAL, "RC not calibrated");
gcs_chan.send_text(MAV_SEVERITY_CRITICAL, "遥控器未校准");//RC not calibrated
ap.compass_mot = false;
return MAV_RESULT_TEMPORARILY_REJECTED;
}
@ -60,14 +60,14 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan) @@ -60,14 +60,14 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan)
// check throttle is at zero
read_radio();
if (channel_throttle->get_control_in() != 0) {
gcs_chan.send_text(MAV_SEVERITY_CRITICAL, "Throttle not zero");
gcs_chan.send_text(MAV_SEVERITY_CRITICAL, "油门不为0");//Throttle not zero
ap.compass_mot = false;
return MAV_RESULT_TEMPORARILY_REJECTED;
}
// check we are landed
if (!ap.land_complete) {
gcs_chan.send_text(MAV_SEVERITY_CRITICAL, "Not landed");
gcs_chan.send_text(MAV_SEVERITY_CRITICAL, "未降落");//Not landed
ap.compass_mot = false;
return MAV_RESULT_TEMPORARILY_REJECTED;
}
@ -91,7 +91,7 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan) @@ -91,7 +91,7 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan)
AP_Notify::flags.esc_calibration = true;
// warn user we are starting calibration
gcs_chan.send_text(MAV_SEVERITY_INFO, "Starting calibration");
gcs_chan.send_text(MAV_SEVERITY_INFO, "开始校准");//Starting calibration
// inform what type of compensation we are attempting
if (comp_type == AP_COMPASS_MOT_COMP_CURRENT) {

4
ArduCopter/crash_check.cpp

@ -65,7 +65,7 @@ void Copter::crash_check() @@ -65,7 +65,7 @@ void Copter::crash_check()
// keep logging even if disarmed:
AP::logger().set_force_log_disarmed(true);
// send message to gcs
gcs().send_text(MAV_SEVERITY_EMERGENCY,"Crash: Disarming");
gcs().send_text(MAV_SEVERITY_EMERGENCY,"坠机:锁定");//Crash: Disarming
// disarm motors
copter.arming.disarm();
}
@ -135,7 +135,7 @@ void Copter::thrust_loss_check() @@ -135,7 +135,7 @@ void Copter::thrust_loss_check()
thrust_loss_counter = 0;
AP::logger().Write_Error(LogErrorSubsystem::THRUST_LOSS_CHECK, LogErrorCode::FAILSAFE_OCCURRED);
// send message to gcs
gcs().send_text(MAV_SEVERITY_EMERGENCY, "Potential Thrust Loss (%d)", (int)motors->get_lost_motor() + 1);
gcs().send_text(MAV_SEVERITY_EMERGENCY, "潜在的推力损失 (%d)", (int)motors->get_lost_motor() + 1); //Potential Thrust Loss
// enable thrust loss handling
motors->set_thrust_boost(true);
// the motors library disables this when it is no longer needed to achieve the commanded output

6
ArduCopter/ekf_check.cpp

@ -64,7 +64,7 @@ void Copter::ekf_check() @@ -64,7 +64,7 @@ void Copter::ekf_check()
AP::logger().Write_Error(LogErrorSubsystem::EKFCHECK, LogErrorCode::EKFCHECK_BAD_VARIANCE);
// send message to gcs
if ((AP_HAL::millis() - ekf_check_state.last_warn_time) > EKF_CHECK_WARNING_TIME) {
gcs().send_text(MAV_SEVERITY_CRITICAL,"EKF variance");
gcs().send_text(MAV_SEVERITY_CRITICAL,"EKF不佳"); //EKF variance
ekf_check_state.last_warn_time = AP_HAL::millis();
}
failsafe_ekf_event();
@ -247,7 +247,7 @@ void Copter::check_vibration() @@ -247,7 +247,7 @@ void Copter::check_vibration()
pos_control->set_vibe_comp(false);
vibration_check.clear_ms = 0;
AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_VIBE, LogErrorCode::FAILSAFE_RESOLVED);
gcs().send_text(MAV_SEVERITY_CRITICAL, "Vibration compensation OFF");
gcs().send_text(MAV_SEVERITY_CRITICAL, "震动补偿关闭");//Vibration compensation OFF
}
}
vibration_check.start_ms = 0;
@ -268,7 +268,7 @@ void Copter::check_vibration() @@ -268,7 +268,7 @@ void Copter::check_vibration()
vibration_check.high_vibes = true;
pos_control->set_vibe_comp(true);
AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_VIBE, LogErrorCode::FAILSAFE_OCCURRED);
gcs().send_text(MAV_SEVERITY_CRITICAL, "Vibration compensation ON");
gcs().send_text(MAV_SEVERITY_CRITICAL, "启用震动补偿"); //Vibration compensation ON
}
}
}

2
ArduCopter/esc_calibration.cpp

@ -39,7 +39,7 @@ void Copter::esc_calibration_startup_check() @@ -39,7 +39,7 @@ void Copter::esc_calibration_startup_check()
// we will enter esc_calibrate mode on next reboot
g.esc_calibrate.set_and_save(ESCCalibrationModes::ESCCAL_PASSTHROUGH_IF_THROTTLE_HIGH);
// send message to gcs
gcs().send_text(MAV_SEVERITY_CRITICAL,"ESC calibration: Restart board");
gcs().send_text(MAV_SEVERITY_CRITICAL,"电调校准:重启底板");//ESC calibration: Restart board
// turn on esc calibration notification
AP_Notify::flags.esc_calibration = true;
// block until we restart

6
ArduCopter/events.cpp

@ -274,7 +274,7 @@ void Copter::failsafe_terrain_set_status(bool data_ok) @@ -274,7 +274,7 @@ void Copter::failsafe_terrain_set_status(bool data_ok)
void Copter::failsafe_terrain_on_event()
{
failsafe.terrain = true;
gcs().send_text(MAV_SEVERITY_CRITICAL,"Failsafe: Terrain data missing");
gcs().send_text(MAV_SEVERITY_CRITICAL,"故障保护:地形数据丢失");//Failsafe: Terrain data missing
AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_TERRAIN, LogErrorCode::FAILSAFE_OCCURRED);
if (should_disarm_on_failsafe()) {
@ -300,10 +300,10 @@ void Copter::gpsglitch_check() @@ -300,10 +300,10 @@ void Copter::gpsglitch_check()
ap.gps_glitching = gps_glitching;
if (gps_glitching) {
AP::logger().Write_Error(LogErrorSubsystem::GPS, LogErrorCode::GPS_GLITCH);
gcs().send_text(MAV_SEVERITY_CRITICAL,"GPS Glitch");
gcs().send_text(MAV_SEVERITY_CRITICAL,"GPS信号异常"); //GPS Glitch
} else {
AP::logger().Write_Error(LogErrorSubsystem::GPS, LogErrorCode::ERROR_RESOLVED);
gcs().send_text(MAV_SEVERITY_CRITICAL,"GPS Glitch cleared");
gcs().send_text(MAV_SEVERITY_CRITICAL,"清除GPS信号异常");//GPS Glitch cleared
}
}
}

10
ArduCopter/mode.cpp

@ -194,7 +194,7 @@ bool Copter::set_mode(Mode::Number mode, ModeReason reason) @@ -194,7 +194,7 @@ bool Copter::set_mode(Mode::Number mode, ModeReason reason)
Mode *new_flightmode = mode_from_mode_num((Mode::Number)mode);
if (new_flightmode == nullptr) {
gcs().send_text(MAV_SEVERITY_WARNING,"No such mode");
gcs().send_text(MAV_SEVERITY_WARNING,"没有这个模式");//No such mode
AP::logger().Write_Error(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(mode));
return false;
}
@ -216,7 +216,7 @@ bool Copter::set_mode(Mode::Number mode, ModeReason reason) @@ -216,7 +216,7 @@ bool Copter::set_mode(Mode::Number mode, ModeReason reason)
#endif
if (!in_autorotation_check) {
gcs().send_text(MAV_SEVERITY_WARNING,"Flight mode change failed");
gcs().send_text(MAV_SEVERITY_WARNING,"模式切换失败");//Flight mode change failed
AP::logger().Write_Error(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(mode));
return false;
}
@ -245,7 +245,7 @@ bool Copter::set_mode(Mode::Number mode, ModeReason reason) @@ -245,7 +245,7 @@ bool Copter::set_mode(Mode::Number mode, ModeReason reason)
user_throttle &&
!copter.flightmode->has_manual_throttle() &&
new_flightmode->get_pilot_desired_throttle() > copter.get_non_takeoff_throttle()) {
gcs().send_text(MAV_SEVERITY_WARNING, "Mode change failed: throttle too high");
gcs().send_text(MAV_SEVERITY_WARNING, "模式切换失败, 油门太高");//Mode change failed: throttle too high
AP::logger().Write_Error(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(mode));
return false;
}
@ -254,13 +254,13 @@ bool Copter::set_mode(Mode::Number mode, ModeReason reason) @@ -254,13 +254,13 @@ bool Copter::set_mode(Mode::Number mode, ModeReason reason)
if (!ignore_checks &&
new_flightmode->requires_GPS() &&
!copter.position_ok()) {
gcs().send_text(MAV_SEVERITY_WARNING, "Mode change failed: %s requires position", new_flightmode->name());
gcs().send_text(MAV_SEVERITY_WARNING, "模式切换失败, %s 需要位置信息", new_flightmode->name());
AP::logger().Write_Error(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(mode));
return false;
}
if (!new_flightmode->init(ignore_checks)) {
gcs().send_text(MAV_SEVERITY_WARNING,"Flight mode change failed");
gcs().send_text(MAV_SEVERITY_WARNING,"模式切换失败");//Flight mode change failed
AP::logger().Write_Error(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(mode));
return false;
}

2
ArduCopter/mode_auto.cpp

@ -27,7 +27,7 @@ bool ModeAuto::init(bool ignore_checks) @@ -27,7 +27,7 @@ bool ModeAuto::init(bool ignore_checks)
// reject switching to auto mode if landed with motors armed but first command is not a takeoff (reduce chance of flips)
if (motors->armed() && copter.ap.land_complete && !mission.starts_with_takeoff_cmd()) {
gcs().send_text(MAV_SEVERITY_CRITICAL, "Auto: Missing Takeoff Cmd");
gcs().send_text(MAV_SEVERITY_CRITICAL, "自动模式:丢失起飞命令"); //Auto: Missing Takeoff Cmd
return false;
}

2
ArduCopter/mode_land.cpp

@ -36,7 +36,7 @@ bool ModeLand::init(bool ignore_checks) @@ -36,7 +36,7 @@ bool ModeLand::init(bool ignore_checks)
// initialise yaw
auto_yaw.set_mode(AUTO_YAW_HOLD);
gcs().send_text(MAV_SEVERITY_INFO,"NOTICE: 开始降落");
return true;
}

2
ArduCopter/mode_rtl.cpp

@ -33,7 +33,7 @@ void ModeRTL::restart_without_terrain() @@ -33,7 +33,7 @@ void ModeRTL::restart_without_terrain()
terrain_following_allowed = false;
_state = RTL_Starting;
_state_complete = true;
gcs().send_text(MAV_SEVERITY_CRITICAL,"Restarting RTL - Terrain data missing");
gcs().send_text(MAV_SEVERITY_CRITICAL,"重启返航-缺少地形数据");//Restarting RTL - Terrain data missing
}
}

4
ArduPlane/AP_Arming.cpp

@ -149,13 +149,13 @@ bool AP_Arming_Plane::arm_checks(AP_Arming::Method method) @@ -149,13 +149,13 @@ bool AP_Arming_Plane::arm_checks(AP_Arming::Method method)
#if GEOFENCE_ENABLED == ENABLED
if (plane.g.fence_autoenable == 3) {
if (!plane.geofence_set_enabled(true)) {
gcs().send_text(MAV_SEVERITY_WARNING, "Fence: cannot enable for arming");
gcs().send_text(MAV_SEVERITY_WARNING, "围栏:无法解锁");//Fence: cannot enable for arming
return false;
} else if (!plane.geofence_prearm_check()) {
plane.geofence_set_enabled(false);
return false;
} else {
gcs().send_text(MAV_SEVERITY_WARNING, "Fence: auto-enabled for arming");
gcs().send_text(MAV_SEVERITY_WARNING, "围栏:自动启用解锁");//Fence: auto-enabled for arming
}
}
#endif

90
libraries/AP_Arming/AP_Arming.cpp

@ -201,7 +201,7 @@ bool AP_Arming::barometer_checks(bool report) @@ -201,7 +201,7 @@ bool AP_Arming::barometer_checks(bool report)
if ((checks_to_perform & ARMING_CHECK_ALL) ||
(checks_to_perform & ARMING_CHECK_BARO)) {
if (!AP::baro().all_healthy()) {
check_failed(ARMING_CHECK_BARO, report, "Barometer not healthy");
check_failed(ARMING_CHECK_BARO, report, "气压计不健康"); //Barometer not healthy
return false;
}
}
@ -220,7 +220,7 @@ bool AP_Arming::airspeed_checks(bool report) @@ -220,7 +220,7 @@ bool AP_Arming::airspeed_checks(bool report)
}
for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
if (airspeed->enabled(i) && airspeed->use(i) && !airspeed->healthy(i)) {
check_failed(ARMING_CHECK_AIRSPEED, report, "Airspeed %d not healthy", i + 1);
check_failed(ARMING_CHECK_AIRSPEED, report, "空速计 %d 不健康", i + 1);//Airspeed %d not healthy
return false;
}
}
@ -238,11 +238,11 @@ bool AP_Arming::logging_checks(bool report) @@ -238,11 +238,11 @@ bool AP_Arming::logging_checks(bool report)
return true;
}
if (AP::logger().logging_failed()) {
check_failed(ARMING_CHECK_LOGGING, report, "Logging failed");
check_failed(ARMING_CHECK_LOGGING, report, "日志记录错误");//Logging failed
return false;
}
if (!AP::logger().CardInserted()) {
check_failed(ARMING_CHECK_LOGGING, report, "No SD card");
check_failed(ARMING_CHECK_LOGGING, report, "无SD卡");//No SD card
return false;
}
}
@ -325,37 +325,37 @@ bool AP_Arming::ins_checks(bool report) @@ -325,37 +325,37 @@ bool AP_Arming::ins_checks(bool report)
(checks_to_perform & ARMING_CHECK_INS)) {
const AP_InertialSensor &ins = AP::ins();
if (!ins.get_gyro_health_all()) {
check_failed(ARMING_CHECK_INS, report, "Gyros not healthy");
check_failed(ARMING_CHECK_INS, report, "陀螺仪不健康");//Gyros not healthy
return false;
}
if (!ins.gyro_calibrated_ok_all()) {
check_failed(ARMING_CHECK_INS, report, "Gyros not calibrated");
check_failed(ARMING_CHECK_INS, report, "陀螺仪需要校准");//Gyros not calibrated
return false;
}
if (!ins.get_accel_health_all()) {
check_failed(ARMING_CHECK_INS, report, "Accels not healthy");
check_failed(ARMING_CHECK_INS, report, "加速度计不健康");//Accels not healthy
return false;
}
if (!ins.accel_calibrated_ok_all()) {
check_failed(ARMING_CHECK_INS, report, "3D Accel calibration needed");
check_failed(ARMING_CHECK_INS, report, "3D加速度计需要校准");//3D Accel calibration needed
return false;
}
//check if accelerometers have calibrated and require reboot
if (ins.accel_cal_requires_reboot()) {
check_failed(ARMING_CHECK_INS, report, "Accels calibrated requires reboot");
check_failed(ARMING_CHECK_INS, report, "加速度计校准后需重启");//Accels calibrated requires reboot
return false;
}
// check all accelerometers point in roughly same direction
if (!ins_accels_consistent(ins)) {
check_failed(ARMING_CHECK_INS, report, "Accels inconsistent");
check_failed(ARMING_CHECK_INS, report, "加速度计值不一致");//Accels inconsistent
return false;
}
// check all gyros are giving consistent readings
if (!ins_gyros_consistent(ins)) {
check_failed(ARMING_CHECK_INS, report, "Gyros inconsistent");
check_failed(ARMING_CHECK_INS, report, "陀螺仪值不一致"); //Gyros inconsistent
return false;
}
@ -376,13 +376,13 @@ bool AP_Arming::compass_checks(bool report) @@ -376,13 +376,13 @@ bool AP_Arming::compass_checks(bool report)
// check if compass is calibrating
if (_compass.is_calibrating()) {
check_failed(report, "Compass calibration running");
check_failed(report, "正在校准指南针....");//Compass calibration running
return false;
}
// check if compass has calibrated and requires reboot
if (_compass.compass_cal_requires_reboot()) {
check_failed(report, "Compass calibrated requires reboot");
check_failed(report, "指南针校准后需重启");//Compass calibrated requires reboot
return false;
}
@ -397,32 +397,32 @@ bool AP_Arming::compass_checks(bool report) @@ -397,32 +397,32 @@ bool AP_Arming::compass_checks(bool report)
}
if (!_compass.healthy()) {
check_failed(ARMING_CHECK_COMPASS, report, "Compass not healthy");
check_failed(ARMING_CHECK_COMPASS, report, "指南针不健康");//Compass not healthy
return false;
}
// check compass learning is on or offsets have been set
if (!_compass.learn_offsets_enabled() && !_compass.configured()) {
check_failed(ARMING_CHECK_COMPASS, report, "Compass not calibrated");
check_failed(ARMING_CHECK_COMPASS, report, "指南针需要校准");//Compass not calibrated
return false;
}
// check for unreasonable compass offsets
const Vector3f offsets = _compass.get_offsets();
if (offsets.length() > _compass.get_offsets_max()) {
check_failed(ARMING_CHECK_COMPASS, report, "Compass offsets too high");
check_failed(ARMING_CHECK_COMPASS, report, "指南针偏移过大");//Compass offsets too high
return false;
}
// check for unreasonable mag field length
const float mag_field = _compass.get_field().length();
if (mag_field > AP_ARMING_COMPASS_MAGFIELD_MAX || mag_field < AP_ARMING_COMPASS_MAGFIELD_MIN) {
check_failed(ARMING_CHECK_COMPASS, report, "Check mag field");
check_failed(ARMING_CHECK_COMPASS, report, "磁力计检查错误");//Check mag field
return false;
}
// check all compasses point in roughly same direction
if (!_compass.consistent()) {
check_failed(ARMING_CHECK_COMPASS, report, "Compasses inconsistent");
check_failed(ARMING_CHECK_COMPASS, report, "指南针不一致");//Compasses inconsistent
return false;
}
}
@ -438,25 +438,25 @@ bool AP_Arming::gps_checks(bool report) @@ -438,25 +438,25 @@ bool AP_Arming::gps_checks(bool report)
//GPS OK?
if (!AP::ahrs().home_is_set() ||
gps.status() < AP_GPS::GPS_OK_FIX_3D) {
check_failed(ARMING_CHECK_GPS, report, "Bad GPS Position");
check_failed(ARMING_CHECK_GPS, report, "GPS位置值不佳");//Bad GPS Position
return false;
}
//GPS update rate acceptable
if (!gps.is_healthy()) {
check_failed(ARMING_CHECK_GPS, report, "GPS is not healthy");
check_failed(ARMING_CHECK_GPS, report, "GPS不健康");//GPS is not healthy
return false;
}
// check GPSs are within 50m of each other and that blending is healthy
float distance_m;
if (!gps.all_consistent(distance_m)) {
check_failed(ARMING_CHECK_GPS, report, "GPS positions differ by %4.1fm",
check_failed(ARMING_CHECK_GPS, report, "GPS位置相差 %4.1f米",//GPS positions differ by %4.1fm
(double)distance_m);
return false;
}
if (!gps.blend_health_check()) {
check_failed(ARMING_CHECK_GPS, report, "GPS blending unhealthy");
check_failed(ARMING_CHECK_GPS, report, "GPS混合值不健康");//GPS blending unhealthy
return false;
}
@ -466,7 +466,7 @@ bool AP_Arming::gps_checks(bool report) @@ -466,7 +466,7 @@ bool AP_Arming::gps_checks(bool report)
if (AP::ahrs().get_position(ahrs_loc)) {
const float distance = gps_loc.get_distance(ahrs_loc);
if (distance > AP_ARMING_AHRS_GPS_ERROR_MAX) {
check_failed(ARMING_CHECK_GPS, report, "GPS and AHRS differ by %4.1fm", (double)distance);
check_failed(ARMING_CHECK_GPS, report, "GPS与姿态解算值 相差%4.1f米", (double)distance);//GPS and AHRS differ by %4.1fm
return false;
}
}
@ -477,8 +477,8 @@ bool AP_Arming::gps_checks(bool report) @@ -477,8 +477,8 @@ bool AP_Arming::gps_checks(bool report)
if (gps.first_unconfigured_gps(first_unconfigured)) {
check_failed(ARMING_CHECK_GPS_CONFIG,
report,
"GPS %d failing configuration checks",
first_unconfigured + 1);
"GPS%d配置检查失败",
first_unconfigured + 1);//GPS %d failing configuration checks
if (report) {
gps.broadcast_first_configuration_failure_reason();
}
@ -510,7 +510,7 @@ bool AP_Arming::hardware_safety_check(bool report) @@ -510,7 +510,7 @@ bool AP_Arming::hardware_safety_check(bool report)
// check if safety switch has been pushed
if (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) {
check_failed(ARMING_CHECK_SWITCH, report, "Hardware safety switch");
check_failed(ARMING_CHECK_SWITCH, report, "硬件安全开关"); //Hardware safety switch
return false;
}
}
@ -550,7 +550,7 @@ bool AP_Arming::manual_transmitter_checks(bool report) @@ -550,7 +550,7 @@ bool AP_Arming::manual_transmitter_checks(bool report)
(checks_to_perform & ARMING_CHECK_RC)) {
if (AP_Notify::flags.failsafe_radio) {
check_failed(ARMING_CHECK_RC, report, "Radio failsafe on");
check_failed(ARMING_CHECK_RC, report, "遥控器故障保护开启"); //Radio failsafe on
return false;
}
@ -568,7 +568,7 @@ bool AP_Arming::mission_checks(bool report) @@ -568,7 +568,7 @@ bool AP_Arming::mission_checks(bool report)
_required_mission_items) {
AP_Mission *mission = AP::mission();
if (mission == nullptr) {
check_failed(ARMING_CHECK_MISSION, report, "No mission library present");
check_failed(ARMING_CHECK_MISSION, report, "无任务库"); //No mission library present
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
AP_HAL::panic("Mission checks requested, but no mission was allocated");
#endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL
@ -576,7 +576,7 @@ bool AP_Arming::mission_checks(bool report) @@ -576,7 +576,7 @@ bool AP_Arming::mission_checks(bool report)
}
AP_Rally *rally = AP::rally();
if (rally == nullptr) {
check_failed(ARMING_CHECK_MISSION, report, "No rally library present");
check_failed(ARMING_CHECK_MISSION, report, "无集结点库");//No rally library present
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
AP_HAL::panic("Mission checks requested, but no rally was allocated");
#endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL
@ -597,7 +597,7 @@ bool AP_Arming::mission_checks(bool report) @@ -597,7 +597,7 @@ bool AP_Arming::mission_checks(bool report)
for (uint8_t i = 0; i < ARRAY_SIZE(misChecks); i++) {
if (_required_mission_items & misChecks[i].check) {
if (!mission->contains_item(misChecks[i].mis_item_type)) {
check_failed(ARMING_CHECK_MISSION, report, "Missing mission item: %s", misChecks[i].type);
check_failed(ARMING_CHECK_MISSION, report, "缺少任务项: %s", misChecks[i].type);//"Missing mission item: %s"
return false;
}
}
@ -605,12 +605,12 @@ bool AP_Arming::mission_checks(bool report) @@ -605,12 +605,12 @@ bool AP_Arming::mission_checks(bool report)
if (_required_mission_items & MIS_ITEM_CHECK_RALLY) {
Location ahrs_loc;
if (!AP::ahrs().get_position(ahrs_loc)) {
check_failed(ARMING_CHECK_MISSION, report, "Can't check rally without position");
check_failed(ARMING_CHECK_MISSION, report, "无姿态解算位置,无法检查集结点"); //Can't check rally without position
return false;
}
RallyLocation rally_loc = {};
if (!rally->find_nearest_rally_point(ahrs_loc, rally_loc)) {
check_failed(ARMING_CHECK_MISSION, report, "No sufficently close rally point located");
check_failed(ARMING_CHECK_MISSION, report, "没有足够接近的集结点");//No sufficently close rally point located
return false;
}
}
@ -648,7 +648,7 @@ bool AP_Arming::servo_checks(bool report) const @@ -648,7 +648,7 @@ bool AP_Arming::servo_checks(bool report) const
const uint16_t trim = c->get_trim();
if (c->get_output_min() > trim) {
check_failed(report, "SERVO%d minimum is greater than trim", i + 1);
check_failed(report, "SERVO%d minimum is greater than trim", i + 1);
check_passed = false;
}
if (c->get_output_max() < trim) {
@ -659,7 +659,7 @@ bool AP_Arming::servo_checks(bool report) const @@ -659,7 +659,7 @@ bool AP_Arming::servo_checks(bool report) const
#if HAL_WITH_IO_MCU
if (!iomcu.healthy()) {
check_failed(report, "IOMCU is unhealthy");
check_failed(report, "IO控制器不健康"); //IOMCU is unhealthy
check_passed = false;
}
#endif
@ -675,7 +675,7 @@ bool AP_Arming::board_voltage_checks(bool report) @@ -675,7 +675,7 @@ bool AP_Arming::board_voltage_checks(bool report)
const float bus_voltage = hal.analogin->board_voltage();
const float vbus_min = AP_BoardConfig::get_minimum_board_voltage();
if(((bus_voltage < vbus_min) || (bus_voltage > AP_ARMING_BOARD_VOLTAGE_MAX))) {
check_failed(ARMING_CHECK_VOLTAGE, report, "Board (%1.1fv) out of range %1.1f-%1.1fv", (double)bus_voltage, (double)vbus_min, (double)AP_ARMING_BOARD_VOLTAGE_MAX);
check_failed(ARMING_CHECK_VOLTAGE, report, "板载电压 (%1.1fv) 超出范围 %1.1f-%1.1fv", (double)bus_voltage, (double)vbus_min, (double)AP_ARMING_BOARD_VOLTAGE_MAX);//Board (%1.1fv) out of range %1.1f-%1.1fv
return false;
}
#endif // HAL_HAVE_BOARD_VOLTAGE
@ -685,7 +685,7 @@ bool AP_Arming::board_voltage_checks(bool report) @@ -685,7 +685,7 @@ bool AP_Arming::board_voltage_checks(bool report)
if (is_positive(vservo_min)) {
const float servo_voltage = hal.analogin->servorail_voltage();
if (servo_voltage < vservo_min) {
check_failed(ARMING_CHECK_VOLTAGE, report, "Servo voltage to low (%1.2fv < %1.2fv)", (double)servo_voltage, (double)vservo_min);
check_failed(ARMING_CHECK_VOLTAGE, report, "伺服电压过低 (%1.2fv < %1.2fv)", (double)servo_voltage, (double)vservo_min);//Servo voltage to low
return false;
}
}
@ -702,26 +702,26 @@ bool AP_Arming::system_checks(bool report) @@ -702,26 +702,26 @@ bool AP_Arming::system_checks(bool report)
{
if (check_enabled(ARMING_CHECK_SYSTEM)) {
if (!hal.storage->healthy()) {
check_failed(ARMING_CHECK_SYSTEM, report, "Param storage failed");
check_failed(ARMING_CHECK_SYSTEM, report, "参数保存错误"); //Param storage failed
return false;
}
#if AP_TERRAIN_AVAILABLE
const AP_Terrain *terrain = AP_Terrain::get_singleton();
if ((terrain != nullptr) && terrain->init_failed()) {
check_failed(ARMING_CHECK_SYSTEM, report, "Terrain out of memory");
check_failed(ARMING_CHECK_SYSTEM, report, "地形内存不足");//Terrain out of memory
return false;
}
#endif
#ifdef ENABLE_SCRIPTING
const AP_Scripting *scripting = AP_Scripting::get_singleton();
if ((scripting != nullptr) && scripting->enabled() && scripting->init_failed()) {
check_failed(ARMING_CHECK_SYSTEM, report, "Scripting out of memory");
check_failed(ARMING_CHECK_SYSTEM, report, "脚本超出内存");//Scripting out of memory
return false;
}
#endif
}
if (AP::internalerror().errors() != 0) {
check_failed(report, "Internal errors (0x%x)", (unsigned int)AP::internalerror().errors());
check_failed(report, "内部错误 (0x%x)", (unsigned int)AP::internalerror().errors());//Internal errors
return false;
}
@ -743,7 +743,7 @@ bool AP_Arming::proximity_checks(bool report) const @@ -743,7 +743,7 @@ bool AP_Arming::proximity_checks(bool report) const
// return false if proximity sensor unhealthy
if (proximity->get_status() < AP_Proximity::Status::Good) {
check_failed(report, "check proximity sensor");
check_failed(report, "检查接近传感器");//check proximity sensor
return false;
}
@ -763,7 +763,7 @@ bool AP_Arming::can_checks(bool report) @@ -763,7 +763,7 @@ bool AP_Arming::can_checks(bool report)
// To be replaced with macro saying if KDECAN library is included
#if APM_BUILD_TYPE(APM_BUILD_ArduCopter) || APM_BUILD_TYPE(APM_BUILD_ArduPlane) || APM_BUILD_TYPE(APM_BUILD_ArduSub)
AP_KDECAN *ap_kdecan = AP_KDECAN::get_kdecan(i);
snprintf(fail_msg, ARRAY_SIZE(fail_msg), "KDECAN failed");
snprintf(fail_msg, ARRAY_SIZE(fail_msg), "KDECAN失效"); //KDECAN failed
if (ap_kdecan != nullptr && !ap_kdecan->pre_arm_check(fail_msg, ARRAY_SIZE(fail_msg))) {
check_failed(ARMING_CHECK_SYSTEM, report, "%s", fail_msg);
return false;
@ -773,7 +773,7 @@ bool AP_Arming::can_checks(bool report) @@ -773,7 +773,7 @@ bool AP_Arming::can_checks(bool report)
}
case AP_BoardConfig_CAN::Protocol_Type_UAVCAN:
{
snprintf(fail_msg, ARRAY_SIZE(fail_msg), "UAVCAN failed");
snprintf(fail_msg, ARRAY_SIZE(fail_msg), "UAVCAN失效");//UAVCAN failed
if (!AP::uavcan_server().prearm_check(fail_msg, ARRAY_SIZE(fail_msg))) {
check_failed(ARMING_CHECK_SYSTEM, report, "%s", fail_msg);
return false;
@ -804,7 +804,7 @@ bool AP_Arming::fence_checks(bool display_failure) @@ -804,7 +804,7 @@ bool AP_Arming::fence_checks(bool display_failure)
}
if (fail_msg == nullptr) {
check_failed(display_failure, "Check fence");
check_failed(display_failure, "检查围栏"); //Check fence
} else {
check_failed(display_failure, "%s", fail_msg);
}
@ -863,7 +863,7 @@ bool AP_Arming::arm_checks(AP_Arming::Method method) @@ -863,7 +863,7 @@ bool AP_Arming::arm_checks(AP_Arming::Method method)
if (!logger->logging_started() &&
((checks_to_perform & ARMING_CHECK_ALL) ||
(checks_to_perform & ARMING_CHECK_LOGGING))) {
check_failed(ARMING_CHECK_LOGGING, true, "Logging not started");
check_failed(ARMING_CHECK_LOGGING, true, "日志记录未启动"); //Logging not started
return false;
}
}

6
libraries/AP_BattMonitor/AP_BattMonitor.cpp

@ -365,7 +365,7 @@ void AP_BattMonitor::check_failsafes(void) @@ -365,7 +365,7 @@ void AP_BattMonitor::check_failsafes(void)
break;
}
gcs().send_text(MAV_SEVERITY_WARNING, "Battery %d is %s %.2fV used %.0f mAh", i + 1, type_str,
gcs().send_text(MAV_SEVERITY_WARNING, "电池 %d 类型 %s %.2fV used %.0f mAh", i + 1, type_str, //Battery %d is %s %.2fV used %.0f mAh
(double)voltage(i), (double)state[i].consumed_mah);
_has_triggered_failsafe = true;
AP_Notify::flags.failsafe_battery = true;
@ -452,7 +452,7 @@ bool AP_BattMonitor::arming_checks(size_t buflen, char *buffer) const @@ -452,7 +452,7 @@ bool AP_BattMonitor::arming_checks(size_t buflen, char *buffer) const
for (uint8_t i = 0; i < AP_BATT_MONITOR_MAX_INSTANCES; i++) {
if (drivers[i] != nullptr && !(drivers[i]->arming_checks(temp_buffer, sizeof(temp_buffer)))) {
hal.util->snprintf(buffer, buflen, "Battery %d %s", i + 1, temp_buffer);
hal.util->snprintf(buffer, buflen, "电池 %d: %s", i + 1, temp_buffer); //Battery %d %s
return false;
}
}
@ -473,7 +473,7 @@ void AP_BattMonitor::checkPoweringOff(void) @@ -473,7 +473,7 @@ void AP_BattMonitor::checkPoweringOff(void)
cmd_msg.command = MAV_CMD_POWER_OFF_INITIATED;
cmd_msg.param1 = i+1;
GCS_MAVLINK::send_to_components(MAVLINK_MSG_ID_COMMAND_LONG, (char*)&cmd_msg, sizeof(cmd_msg));
gcs().send_text(MAV_SEVERITY_WARNING, "Vehicle %d battery %d is powering off", mavlink_system.sysid, i+1);
gcs().send_text(MAV_SEVERITY_WARNING, "无人机 %d 电池 %d 正在关闭", mavlink_system.sysid, i+1); //Vehicle %d battery %d is powering off
// only send this once
state[i].powerOffNotified = true;

42
libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp

@ -169,22 +169,30 @@ bool AP_BattMonitor_Backend::arming_checks(char * buffer, size_t buflen) const @@ -169,22 +169,30 @@ bool AP_BattMonitor_Backend::arming_checks(char * buffer, size_t buflen) const
bool fs_voltage_inversion = is_positive(_params._critical_voltage) &&
is_positive(_params._low_voltage) &&
(_params._low_voltage < _params._critical_voltage);
uint8_t cell_min_index;
uint8_t cell_max_index;
uint16_t dropout_voltage;
uint8_t cell_min_index=0;
uint8_t cell_max_index=0;
uint16_t dropout_voltage=0;
bool fs_cells_dropout_voltage = cells_dropout_voltage_checks(cell_min_index,cell_max_index,dropout_voltage);
bool result = update_check(buflen, buffer, low_voltage, "low voltage failsafe");
result = result && update_check(buflen, buffer, low_capacity, "low capacity failsafe");
result = result && update_check(buflen, buffer, critical_voltage, "critical voltage failsafe");
result = result && update_check(buflen, buffer, critical_capacity, "critical capacity failsafe");
result = result && update_check(buflen, buffer, below_arming_voltage, "below minimum arming voltage");
result = result && update_check(buflen, buffer, below_arming_capacity, "below minimum arming capacity");
result = result && update_check(buflen, buffer, fs_capacity_inversion, "capacity failsafe critical > low");
result = result && update_check(buflen, buffer, fs_voltage_inversion, "voltage failsafe critical > low");
// char bat_message[60];
// snprintf(bat_message,60,"电池压差过大,%d号与%d号电芯,压差 %f V",cell_max_index,cell_min_index,dropout_voltage/1000.0);
result = result && update_check(buflen, buffer, fs_cells_dropout_voltage,"电池压差过大");
bool result = update_check(buflen, buffer, low_voltage, "低电压故障保护");//low voltage failsafe
result = result && update_check(buflen, buffer, low_capacity, "低电量故障保护");//low capacity failsafe
result = result && update_check(buflen, buffer, critical_voltage, "临界电压故障保护");//critical voltage failsafe
result = result && update_check(buflen, buffer, critical_capacity, "临界电量故障保护");//critical capacity failsafe
result = result && update_check(buflen, buffer, below_arming_voltage, "低于最小解锁电压"); //below minimum arming voltage
result = result && update_check(buflen, buffer, below_arming_capacity, "低于最小解锁电量");//below minimum arming capacity
result = result && update_check(buflen, buffer, fs_capacity_inversion, "capacity failsafe critical > low");//capacity failsafe critical > low
result = result && update_check(buflen, buffer, fs_voltage_inversion, "voltage failsafe critical > low");//voltage failsafe critical > low
// char bat_message[60];
// snprintf(bat_message,60,"电池压差过大,%d号与%d号电芯,压差 %f V",cell_max_index,cell_min_index,dropout_voltage/1000.0);
if (dropout_voltage == 0xeeee)
{
result = result && update_check(buflen, buffer, fs_cells_dropout_voltage, "电池电芯可能异常");
}
else
{
result = result && update_check(buflen, buffer, fs_cells_dropout_voltage, "电池压差过大");
}
return result;
}
@ -262,7 +270,7 @@ bool AP_BattMonitor_Backend::cells_dropout_voltage_checks(uint8_t &cell_min_inde @@ -262,7 +270,7 @@ bool AP_BattMonitor_Backend::cells_dropout_voltage_checks(uint8_t &cell_min_inde
uint16_t cell_max = 0;
for (int k = 0; k < MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN; k++)
{
if ((_state.cell_voltages.cells[k]!=65535) && _state.cell_voltages.cells[k] != 0) //TODO if valid cell valtage =0
if ((_state.cell_voltages.cells[k]!=65535)) //TODO if valid cell valtage =0
{
if (_state.cell_voltages.cells[k] < cell_min)
{
@ -282,6 +290,10 @@ bool AP_BattMonitor_Backend::cells_dropout_voltage_checks(uint8_t &cell_min_inde @@ -282,6 +290,10 @@ bool AP_BattMonitor_Backend::cells_dropout_voltage_checks(uint8_t &cell_min_inde
{
return true;
}
if(cell_max ==0&&cell_min==0){
dropout_voltage= 0xeeee; //
return true;
}
}
return false;
}

2
libraries/AP_Compass/AP_Compass_Calibration.cpp

@ -57,7 +57,7 @@ bool Compass::_start_calibration(uint8_t i, bool retry, float delay) @@ -57,7 +57,7 @@ bool Compass::_start_calibration(uint8_t i, bool retry, float delay)
}
if (_options.get() & uint16_t(Option::CAL_REQUIRE_GPS)) {
if (AP::gps().status() < AP_GPS::GPS_OK_FIX_2D) {
gcs().send_text(MAV_SEVERITY_ERROR, "Compass cal requires GPS lock");
gcs().send_text(MAV_SEVERITY_ERROR, "指南针需要GPS锁定");//Compass cal requires GPS lock
return false;
}
}

6
libraries/AP_Compass/CompassCalibrator.cpp

@ -878,13 +878,13 @@ bool CompassCalibrator::calculate_orientation(void) @@ -878,13 +878,13 @@ bool CompassCalibrator::calculate_orientation(void)
pass = _orientation_confidence > variance_threshold;
}
if (!pass) {
gcs().send_text(MAV_SEVERITY_CRITICAL, "Mag(%u) bad orientation: %u/%u %.1f", _compass_idx,
gcs().send_text(MAV_SEVERITY_CRITICAL, "磁力计(%u) 方向不佳: %u/%u %.1f", _compass_idx, //Mag(%u) bad orientation: %u/%u %.1f
besti, besti2, (double)_orientation_confidence);
} else if (besti == _orientation) {
// no orientation change
gcs().send_text(MAV_SEVERITY_INFO, "Mag(%u) good orientation: %u %.1f", _compass_idx, besti, (double)_orientation_confidence);
} else if (!_is_external || !_fix_orientation) {
gcs().send_text(MAV_SEVERITY_CRITICAL, "Mag(%u) internal bad orientation: %u %.1f", _compass_idx, besti, (double)_orientation_confidence);
gcs().send_text(MAV_SEVERITY_CRITICAL, "磁力计(%u) 内部方向不佳: %u %.1f", _compass_idx, besti, (double)_orientation_confidence); //Mag(%u) internal bad orientation: %u %.1f
} else {
gcs().send_text(MAV_SEVERITY_INFO, "Mag(%u) new orientation: %u was %u %.1f", _compass_idx, besti, _orientation, (double)_orientation_confidence);
}
@ -956,7 +956,7 @@ bool CompassCalibrator::fix_radius(void) @@ -956,7 +956,7 @@ bool CompassCalibrator::fix_radius(void)
if (correction > COMPASS_MAX_SCALE_FACTOR || correction < COMPASS_MIN_SCALE_FACTOR) {
// don't allow more than 30% scale factor correction
gcs().send_text(MAV_SEVERITY_ERROR, "Mag(%u) bad radius %.0f expected %.0f",
gcs().send_text(MAV_SEVERITY_ERROR, "磁力计(%u) 半径错误 %.0f,预期为%.0f",//Mag(%u) bad radius %.0f expected %.0f
_compass_idx,
_params.radius,
expected_radius);

4
libraries/AP_Landing/AP_Landing.cpp

@ -212,7 +212,7 @@ bool AP_Landing::verify_land(const Location &prev_WP_loc, Location &next_WP_loc, @@ -212,7 +212,7 @@ bool AP_Landing::verify_land(const Location &prev_WP_loc, Location &next_WP_loc,
default:
// returning TRUE while executing verify_land() will increment the
// mission index which in many cases will trigger an RTL for end-of-mission
gcs().send_text(MAV_SEVERITY_CRITICAL, "Landing configuration error, invalid LAND_TYPE");
gcs().send_text(MAV_SEVERITY_CRITICAL, "着陆设置错误, 无效的着陆类型"); //Landing configuration error, invalid LAND_TYPE
success = true;
break;
}
@ -437,7 +437,7 @@ bool AP_Landing::restart_landing_sequence() @@ -437,7 +437,7 @@ bool AP_Landing::restart_landing_sequence()
gcs().send_text(MAV_SEVERITY_NOTICE, "Restarted landing sequence at waypoint %d", prev_cmd_with_wp_index);
success = true;
} else {
gcs().send_text(MAV_SEVERITY_WARNING, "Unable to restart landing sequence");
gcs().send_text(MAV_SEVERITY_WARNING, "无法重新启动降落排序");//Unable to restart landing sequence
success = false;
}

2
libraries/AP_Logger/AP_Logger_File.cpp

@ -139,7 +139,7 @@ void AP_Logger_File::periodic_1Hz() @@ -139,7 +139,7 @@ void AP_Logger_File::periodic_1Hz()
if (io_thread_warning_decimation_counter == 0 && _initialised) {
// we don't print this error unless we did initialise. When _initialised is set to true
// we register the IO timer callback
gcs().send_text(MAV_SEVERITY_CRITICAL, "AP_Logger: stuck thread (%s)", last_io_operation);
gcs().send_text(MAV_SEVERITY_CRITICAL, "日志记录:线程堵塞(%s)", last_io_operation);//AP_Logger: stuck thread (%s)
}
if (io_thread_warning_decimation_counter++ > 57) {
io_thread_warning_decimation_counter = 0;

4
libraries/AP_Mission/AP_Mission.cpp

@ -1833,7 +1833,7 @@ bool AP_Mission::jump_to_landing_sequence(void) @@ -1833,7 +1833,7 @@ bool AP_Mission::jump_to_landing_sequence(void)
return true;
}
gcs().send_text(MAV_SEVERITY_WARNING, "Unable to start landing sequence");
gcs().send_text(MAV_SEVERITY_WARNING, "无法启用降落排序");//Unable to start landing sequence
return false;
}
@ -1872,7 +1872,7 @@ bool AP_Mission::jump_to_abort_landing_sequence(void) @@ -1872,7 +1872,7 @@ bool AP_Mission::jump_to_abort_landing_sequence(void)
return true;
}
gcs().send_text(MAV_SEVERITY_WARNING, "Unable to start find a landing abort sequence");
gcs().send_text(MAV_SEVERITY_WARNING, "无法查找着陆中止排序");//Unable to start find a landing abort sequence
return false;
}

2
libraries/AP_Motors/AP_MotorsHeli_Quad.cpp

@ -112,7 +112,7 @@ void AP_MotorsHeli_Quad::calculate_armed_scalars() @@ -112,7 +112,7 @@ void AP_MotorsHeli_Quad::calculate_armed_scalars()
// keeps user from changing RSC mode while armed
if (_main_rotor._rsc_mode.get() != _main_rotor.get_control_mode()) {
_main_rotor.reset_rsc_mode_param();
gcs().send_text(MAV_SEVERITY_CRITICAL, "RSC control mode change failed");
gcs().send_text(MAV_SEVERITY_CRITICAL, "RSC control mode change failed");//RSC control mode change failed
_heliflags.save_rsc_mode = true;
}
// saves rsc mode parameter when disarmed if it had been reset while armed

2
libraries/AP_Motors/AP_MotorsTri.cpp

@ -43,7 +43,7 @@ void AP_MotorsTri::init(motor_frame_class frame_class, motor_frame_type frame_ty @@ -43,7 +43,7 @@ void AP_MotorsTri::init(motor_frame_class frame_class, motor_frame_type frame_ty
// find the yaw servo
_yaw_servo = SRV_Channels::get_channel_for(SRV_Channel::k_motor7, AP_MOTORS_CH_TRI_YAW);
if (!_yaw_servo) {
gcs().send_text(MAV_SEVERITY_ERROR, "MotorsTri: unable to setup yaw channel");
gcs().send_text(MAV_SEVERITY_ERROR, "MotorsTri: 无法设置偏航通道");//unable to setup yaw channel
// don't set initialised_ok
return;
}

2
libraries/AP_Motors/AP_Motors_Class.cpp

@ -172,7 +172,7 @@ void AP_Motors::add_motor_num(int8_t motor_num) @@ -172,7 +172,7 @@ void AP_Motors::add_motor_num(int8_t motor_num)
SRV_Channel::Aux_servo_function_t function = SRV_Channels::get_motor_function(motor_num);
SRV_Channels::set_aux_channel_default(function, motor_num);
if (!SRV_Channels::find_channel(function, chan)) {
gcs().send_text(MAV_SEVERITY_ERROR, "Motors: unable to setup motor %u", motor_num);
gcs().send_text(MAV_SEVERITY_ERROR, "Motors: 无法设置电机 %u", motor_num);//unable to setup motor
}
}
}

4
libraries/AP_NavEKF2/AP_NavEKF2.cpp

@ -656,7 +656,7 @@ bool NavEKF2::InitialiseFilter(void) @@ -656,7 +656,7 @@ bool NavEKF2::InitialiseFilter(void)
// check if there is enough memory to create the EKF cores
if (hal.util->available_memory() < sizeof(NavEKF2_core)*num_cores + 4096) {
gcs().send_text(MAV_SEVERITY_CRITICAL, "NavEKF2: not enough memory");
gcs().send_text(MAV_SEVERITY_CRITICAL, "NavEKF2:没有足够的内存");//NavEKF2: not enough memory
_enable.set(0);
return false;
}
@ -665,7 +665,7 @@ bool NavEKF2::InitialiseFilter(void) @@ -665,7 +665,7 @@ bool NavEKF2::InitialiseFilter(void)
core = (NavEKF2_core*)hal.util->malloc_type(sizeof(NavEKF2_core)*num_cores, AP_HAL::Util::MEM_FAST);
if (core == nullptr) {
_enable.set(0);
gcs().send_text(MAV_SEVERITY_CRITICAL, "NavEKF2: allocation failed");
gcs().send_text(MAV_SEVERITY_CRITICAL, "NavEKF2: 分配失败");//NavEKF2: allocation failed
return false;
}

2
libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp

@ -266,7 +266,7 @@ void NavEKF2_core::setAidingMode() @@ -266,7 +266,7 @@ void NavEKF2_core::setAidingMode()
switch (PV_AidingMode) {
case AID_NONE:
// We have ceased aiding
gcs().send_text(MAV_SEVERITY_WARNING, "EKF2 IMU%u has stopped aiding",(unsigned)imu_index);
gcs().send_text(MAV_SEVERITY_WARNING, "EKF2 IMU%u 停止协助",(unsigned)imu_index);//EKF2 IMU%u has stopped aiding
// When not aiding, estimate orientation & height fusing synthetic constant position and zero velocity measurement to constrain tilt errors
posTimeout = true;
velTimeout = true;

6
libraries/AP_NavEKF2/AP_NavEKF2_MagFusion.cpp

@ -142,14 +142,14 @@ void NavEKF2_core::controlMagYawReset() @@ -142,14 +142,14 @@ void NavEKF2_core::controlMagYawReset()
// send initial alignment status to console
if (!yawAlignComplete) {
gcs().send_text(MAV_SEVERITY_INFO, "EKF2 IMU%u initial yaw alignment complete",(unsigned)imu_index);
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
if (finalResetRequest) {
gcs().send_text(MAV_SEVERITY_INFO, "EKF2 IMU%u in-flight yaw alignment complete",(unsigned)imu_index);
gcs().send_text(MAV_SEVERITY_INFO, "EKF2 IMU%u 飞行中偏航调整完成",(unsigned)imu_index); //in-flight yaw alignment complete
} else if (interimResetRequest) {
gcs().send_text(MAV_SEVERITY_WARNING, "EKF2 IMU%u ground mag anomaly, yaw re-aligned",(unsigned)imu_index);
gcs().send_text(MAV_SEVERITY_WARNING, "EKF2 IMU%u 地磁异常,偏航重新对准",(unsigned)imu_index);//EKF2 IMU%u ground mag anomaly, yaw re-aligned
}
// update the yaw reset completed status

2
libraries/AP_NavEKF2/AP_NavEKF2_core.cpp

@ -623,7 +623,7 @@ void NavEKF2_core::UpdateFilter(bool predict) @@ -623,7 +623,7 @@ void NavEKF2_core::UpdateFilter(bool predict)
AP_HAL::millis() - last_filter_ok_ms > 5000 &&
!hal.util->get_soft_armed()) {
// we've been unhealthy for 5 seconds after being healthy, reset the filter
gcs().send_text(MAV_SEVERITY_WARNING, "EKF2 IMU%u forced reset",(unsigned)imu_index);
gcs().send_text(MAV_SEVERITY_WARNING, "EKF2 IMU%u 强制重置",(unsigned)imu_index);//forced reset
last_filter_ok_ms = 0;
statesInitialised = false;
InitialiseFilterBootstrap();

4
libraries/AP_NavEKF3/AP_NavEKF3.cpp

@ -686,7 +686,7 @@ bool NavEKF3::InitialiseFilter(void) @@ -686,7 +686,7 @@ bool NavEKF3::InitialiseFilter(void)
// check if there is enough memory to create the EKF cores
if (hal.util->available_memory() < sizeof(NavEKF3_core)*num_cores + 4096) {
gcs().send_text(MAV_SEVERITY_CRITICAL, "NavEKF3: not enough memory");
gcs().send_text(MAV_SEVERITY_CRITICAL, "NavEKF3: 没有足够的内存");//not enough memory
_enable.set(0);
return false;
}
@ -695,7 +695,7 @@ bool NavEKF3::InitialiseFilter(void) @@ -695,7 +695,7 @@ bool NavEKF3::InitialiseFilter(void)
core = (NavEKF3_core*)hal.util->malloc_type(sizeof(NavEKF3_core)*num_cores, AP_HAL::Util::MEM_FAST);
if (core == nullptr) {
_enable.set(0);
gcs().send_text(MAV_SEVERITY_CRITICAL, "NavEKF3: allocation failed");
gcs().send_text(MAV_SEVERITY_CRITICAL, "NavEKF3: 分配失败");//allocation failed
return false;
}

6
libraries/AP_NavEKF3/AP_NavEKF3_MagFusion.cpp

@ -117,14 +117,14 @@ void NavEKF3_core::controlMagYawReset() @@ -117,14 +117,14 @@ void NavEKF3_core::controlMagYawReset()
// send initial alignment status to console
if (!yawAlignComplete) {
gcs().send_text(MAV_SEVERITY_INFO, "EKF3 IMU%u initial yaw alignment complete",(unsigned)imu_index);
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
if (finalResetRequest) {
gcs().send_text(MAV_SEVERITY_INFO, "EKF3 IMU%u in-flight yaw alignment complete",(unsigned)imu_index);
gcs().send_text(MAV_SEVERITY_INFO, "EKF3 IMU%u飞行中偏航调整完成",(unsigned)imu_index); // in-flight yaw alignment complete
} else if (interimResetRequest) {
gcs().send_text(MAV_SEVERITY_WARNING, "EKF3 IMU%u ground mag anomaly, yaw re-aligned",(unsigned)imu_index);
gcs().send_text(MAV_SEVERITY_WARNING, "EKF3 IMU%u 地磁异常,偏航重校准",(unsigned)imu_index);//ground mag anomaly, yaw re-aligned
}
// prevent reset of variances in ConstrainVariances()

2
libraries/AP_NavEKF3/AP_NavEKF3_VehicleStatus.cpp

@ -96,7 +96,7 @@ void NavEKF3_core::calcGpsGoodToAlign(void) @@ -96,7 +96,7 @@ void NavEKF3_core::calcGpsGoodToAlign(void)
// capable of giving a vertical velocity
if (gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
frontend->_fusionModeGPS.set(1);
gcs().send_text(MAV_SEVERITY_WARNING, "EK3: Changed EK3_GPS_TYPE to 1");
gcs().send_text(MAV_SEVERITY_WARNING, "EK3: EK3 GPS类型改为 1");//将EK3_GPS_TYPE更改为1
}
} else {
gpsVertVelFail = false;

6
libraries/AP_NavEKF3/AP_NavEKF3_core.cpp

@ -75,11 +75,11 @@ bool NavEKF3_core::setup_core(uint8_t _imu_index, uint8_t _core_index) @@ -75,11 +75,11 @@ bool NavEKF3_core::setup_core(uint8_t _imu_index, uint8_t _core_index)
lastInitFailReport_ms = AP_HAL::millis();
// provide an escalating series of messages
if (AP_HAL::millis() > 30000) {
gcs().send_text(MAV_SEVERITY_ERROR, "EKF3 waiting for GPS config data");
gcs().send_text(MAV_SEVERITY_ERROR, "EKF3等待GPS配置数据");//EKF3 waiting for GPS config data
} else if (AP_HAL::millis() > 15000) {
gcs().send_text(MAV_SEVERITY_WARNING, "EKF3 waiting for GPS config data");
gcs().send_text(MAV_SEVERITY_WARNING, "EKF3等待GPS配置数据"); //EKF3 waiting for GPS config data
} else {
gcs().send_text(MAV_SEVERITY_INFO, "EKF3 waiting for GPS config data");
gcs().send_text(MAV_SEVERITY_INFO, "EKF3等待GPS配置数据");//EKF3 waiting for GPS config data
}
}
return false;

8
libraries/AP_Scripting/AP_Scripting.cpp

@ -86,8 +86,8 @@ void AP_Scripting::init(void) { @@ -86,8 +86,8 @@ void AP_Scripting::init(void) {
if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_Scripting::thread, void),
"Scripting", SCRIPTING_STACK_SIZE, AP_HAL::Scheduler::PRIORITY_SCRIPTING, 0)) {
gcs().send_text(MAV_SEVERITY_CRITICAL, "Could not create scripting stack (%d)", SCRIPTING_STACK_SIZE);
gcs().send_text(MAV_SEVERITY_ERROR, "Scripting failed to start");
gcs().send_text(MAV_SEVERITY_CRITICAL, "无法创建脚本堆栈 (%d)", SCRIPTING_STACK_SIZE);//Could not create scripting stack
gcs().send_text(MAV_SEVERITY_ERROR, "脚本启动失败");//Scripting failed to start
_init_failed = true;
}
}
@ -95,14 +95,14 @@ void AP_Scripting::init(void) { @@ -95,14 +95,14 @@ void AP_Scripting::init(void) {
void AP_Scripting::thread(void) {
lua_scripts *lua = new lua_scripts(_script_vm_exec_count, _script_heap_size, _debug_level);
if (lua == nullptr || !lua->heap_allocated()) {
gcs().send_text(MAV_SEVERITY_CRITICAL, "Unable to allocate scripting memory");
gcs().send_text(MAV_SEVERITY_CRITICAL, "无法分配脚本内存");//Unable to allocate scripting memory
_init_failed = true;
return;
}
lua->run();
// only reachable if the lua backend has died for any reason
gcs().send_text(MAV_SEVERITY_CRITICAL, "Scripting has stopped");
gcs().send_text(MAV_SEVERITY_CRITICAL, "脚本已停止");//Scripting has stopped
}
AP_Scripting *AP_Scripting::_singleton = nullptr;

2
libraries/AP_Terrain/AP_Terrain.cpp

@ -384,7 +384,7 @@ bool AP_Terrain::allocate(void) @@ -384,7 +384,7 @@ bool AP_Terrain::allocate(void)
}
cache = (struct grid_cache *)calloc(TERRAIN_GRID_BLOCK_CACHE_SIZE, sizeof(cache[0]));
if (cache == nullptr) {
gcs().send_text(MAV_SEVERITY_CRITICAL, "Terrain: Allocation failed");
gcs().send_text(MAV_SEVERITY_CRITICAL, "地形:分配失败");//Terrain: Allocation failed
memory_alloc_failed = true;
return false;
}

2
libraries/AP_UAVCAN/AP_UAVCAN_Server.cpp

@ -613,7 +613,7 @@ void AP_UAVCAN_Server::handleAllocation(uint8_t driver_index, uint8_t node_id, c @@ -613,7 +613,7 @@ void AP_UAVCAN_Server::handleAllocation(uint8_t driver_index, uint8_t node_id, c
msg.node_id = resp_node_id;
}
} else {
gcs().send_text(MAV_SEVERITY_ERROR, "UC Node Alloc Failed!");
gcs().send_text(MAV_SEVERITY_ERROR, "UAVCAN节点分配失败!");//节点分配失败
}
} else {
msg.node_id = resp_node_id;

2
libraries/GCS_MAVLink/GCS_Param.cpp

@ -275,7 +275,7 @@ void GCS_MAVLINK::handle_param_set(const mavlink_message_t &msg) @@ -275,7 +275,7 @@ void GCS_MAVLINK::handle_param_set(const mavlink_message_t &msg)
float old_value = vp->cast_to_float(var_type);
if ((parameter_flags & AP_PARAM_FLAG_INTERNAL_USE_ONLY) || vp->is_read_only()) {
gcs().send_text(MAV_SEVERITY_WARNING, "Param write denied (%s)", key);
gcs().send_text(MAV_SEVERITY_WARNING, "参数写入被拒绝(%s)", key);//Param write denied (%s)
// echo back the incorrect value so that we fulfull the
// parameter state machine requirements:
send_parameter_value(key, var_type, packet.param_value);

2
libraries/GCS_MAVLink/GCS_Rally.cpp

@ -56,7 +56,7 @@ void GCS_MAVLINK::handle_rally_point(const mavlink_message_t &msg) @@ -56,7 +56,7 @@ void GCS_MAVLINK::handle_rally_point(const mavlink_message_t &msg)
rally_point.flags = packet.flags;
if (!r->set_rally_point_with_index(packet.idx, rally_point)) {
send_text(MAV_SEVERITY_CRITICAL, "Error setting rally point");
send_text(MAV_SEVERITY_CRITICAL, "设置集合点时出错");//Error setting rally point
}
}

4
libraries/GCS_MAVLink/GCS_Signing.cpp

@ -68,7 +68,7 @@ void GCS_MAVLINK::handle_setup_signing(const mavlink_message_t &msg) @@ -68,7 +68,7 @@ void GCS_MAVLINK::handle_setup_signing(const mavlink_message_t &msg)
// setting up signing key when armed generally not useful /
// possibly not a good idea
if (hal.util->get_soft_armed()) {
send_text(MAV_SEVERITY_WARNING, "ERROR: Won't setup signing when armed");
send_text(MAV_SEVERITY_WARNING, "ERROR: 解锁时不会设置签名");//Won't setup signing when armed
return;
}
@ -82,7 +82,7 @@ void GCS_MAVLINK::handle_setup_signing(const mavlink_message_t &msg) @@ -82,7 +82,7 @@ void GCS_MAVLINK::handle_setup_signing(const mavlink_message_t &msg)
memcpy(key.secret_key, packet.secret_key, 32);
if (!signing_key_save(key)) {
send_text(MAV_SEVERITY_WARNING, "ERROR: Failed to save signing key");
send_text(MAV_SEVERITY_WARNING, "ERROR: 保存签名密钥失败");//Failed to save signing key
return;
}

4
libraries/GCS_MAVLink/MissionItemProtocol.cpp

@ -40,7 +40,7 @@ bool MissionItemProtocol::mavlink2_requirement_met(const GCS_MAVLINK &_link, con @@ -40,7 +40,7 @@ bool MissionItemProtocol::mavlink2_requirement_met(const GCS_MAVLINK &_link, con
if (!_link.sending_mavlink1()) {
return true;
}
gcs().send_text(MAV_SEVERITY_WARNING, "Need mavlink2 for item transfer");
gcs().send_text(MAV_SEVERITY_WARNING, "Need mavlink2 for item transfer");//Need mavlink2 for item transfer
send_mission_ack(_link, msg, MAV_MISSION_UNSUPPORTED);
return false;
}
@ -197,7 +197,7 @@ void MissionItemProtocol::handle_mission_write_partial_list(GCS_MAVLINK &_link, @@ -197,7 +197,7 @@ void MissionItemProtocol::handle_mission_write_partial_list(GCS_MAVLINK &_link,
if ((unsigned)packet.start_index > item_count() ||
(unsigned)packet.end_index > item_count() ||
packet.end_index < packet.start_index) {
gcs().send_text(MAV_SEVERITY_WARNING,"Flight plan update rejected"); // FIXME: Remove this anytime after 2020-01-22
gcs().send_text(MAV_SEVERITY_WARNING,"飞行计划更新被拒绝"); // FIXME: Remove this anytime after 2020-01-22
send_mission_ack(_link, msg, MAV_MISSION_ERROR);
return;
}

2
libraries/GCS_MAVLink/MissionItemProtocol_Waypoints.cpp

@ -130,7 +130,7 @@ MAV_MISSION_RESULT MissionItemProtocol_Waypoints::replace_item(const mavlink_mis @@ -130,7 +130,7 @@ MAV_MISSION_RESULT MissionItemProtocol_Waypoints::replace_item(const mavlink_mis
void MissionItemProtocol_Waypoints::timeout()
{
link->send_text(MAV_SEVERITY_WARNING, "Mission upload timeout");
link->send_text(MAV_SEVERITY_WARNING, "任务上传超时 ");//Mission upload timeout
}
void MissionItemProtocol_Waypoints::truncate(const mavlink_mission_count_t &packet)

2
libraries/RC_Channel/RC_Channel.cpp

@ -480,7 +480,7 @@ void RC_Channel::init_aux_function(const aux_func_t ch_option, const aux_switch_ @@ -480,7 +480,7 @@ void RC_Channel::init_aux_function(const aux_func_t ch_option, const aux_switch_
do_aux_function(ch_option, ch_flag);
break;
default:
gcs().send_text(MAV_SEVERITY_WARNING, "Failed to initialise RC function (%u)", (unsigned)ch_option);
gcs().send_text(MAV_SEVERITY_WARNING, "无法初始化遥控器功能 (%u)", (unsigned)ch_option);//Failed to initialise RC function
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
AP_HAL::panic("RC function (%u) initialisation not handled", (unsigned)ch_option);
#endif

Loading…
Cancel
Save