Skip to content

Commit

Permalink
Copter: Share the same wording
Browse files Browse the repository at this point in the history
  • Loading branch information
muramura committed Sep 30, 2024
1 parent ecec9c4 commit 3e43f62
Show file tree
Hide file tree
Showing 6 changed files with 23 additions and 18 deletions.
9 changes: 5 additions & 4 deletions ArduCopter/AP_Arming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -483,20 +483,21 @@ bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure)
float vel_variance, pos_variance, hgt_variance, tas_variance;
Vector3f mag_variance;
ahrs.get_variances(vel_variance, pos_variance, hgt_variance, mag_variance, tas_variance);
const char *fmt = "EKF: %s variance";
if (mag_variance.length() >= copter.g.fs_ekf_thresh) {
check_failed(display_failure, "EKF compass variance");
check_failed(display_failure, fmt, "compass");
return false;
}
if (pos_variance >= copter.g.fs_ekf_thresh) {
check_failed(display_failure, "EKF position variance");
check_failed(display_failure, fmt, "position");
return false;
}
if (vel_variance >= copter.g.fs_ekf_thresh) {
check_failed(display_failure, "EKF velocity variance");
check_failed(display_failure, fmt, "velocity");
return false;
}
if (hgt_variance >= copter.g.fs_ekf_thresh) {
check_failed(display_failure, "EKF height variance");
check_failed(display_failure, fmt, "height");
return false;
}
}
Expand Down
7 changes: 4 additions & 3 deletions ArduCopter/AP_State.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,20 +22,21 @@ void Copter::set_auto_armed(bool b)
void Copter::set_simple_mode(SimpleMode b)
{
if (simple_mode != b) {
const char *flightMode = "SIMPLE mode";
switch (b) {
case SimpleMode::NONE:
LOGGER_WRITE_EVENT(LogEvent::SET_SIMPLE_OFF);
gcs().send_text(MAV_SEVERITY_INFO, "SIMPLE mode off");
gcs().send_text(MAV_SEVERITY_INFO, "%s off", flightMode);
break;
case SimpleMode::SIMPLE:
LOGGER_WRITE_EVENT(LogEvent::SET_SIMPLE_ON);
gcs().send_text(MAV_SEVERITY_INFO, "SIMPLE mode on");
gcs().send_text(MAV_SEVERITY_INFO, "%s on", flightMode);
break;
case SimpleMode::SUPERSIMPLE:
// initialise super simple heading
update_super_simple_bearing(true);
LOGGER_WRITE_EVENT(LogEvent::SET_SUPERSIMPLE_ON);
gcs().send_text(MAV_SEVERITY_INFO, "SUPERSIMPLE mode on");
gcs().send_text(MAV_SEVERITY_INFO, "SUPER%s on", flightMode);
break;
}
simple_mode = b;
Expand Down
4 changes: 4 additions & 0 deletions ArduCopter/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -1520,6 +1520,8 @@ class ModeRTL : public Mode {
IgnorePilotYaw = (1U << 2),
};

const char *flightMode = "RTL";

};


Expand Down Expand Up @@ -1979,6 +1981,8 @@ class ModeZigZag : public Mode {
uint16_t line_count = 0; // current line number
int16_t line_num = 0; // target line number
bool is_suspended; // true if zigzag auto is suspended

const char *dir[4] = {"forward", "right", "backward", "left"};
};

#if MODE_AUTOROTATE_ENABLED
Expand Down
12 changes: 6 additions & 6 deletions ArduCopter/mode_rtl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ void ModeRTL::restart_without_terrain()
terrain_following_allowed = false;
_state = SubMode::STARTING;
_state_complete = true;
gcs().send_text(MAV_SEVERITY_CRITICAL,"Restarting RTL - Terrain data missing");
gcs().send_text(MAV_SEVERITY_CRITICAL,"Restarting %s - Terrain data missing", flightMode);
}

ModeRTL::RTLAltType ModeRTL::get_alt_type() const
Expand Down Expand Up @@ -135,7 +135,7 @@ void ModeRTL::climb_start()
// set the destination
if (!wp_nav->set_wp_destination_loc(rtl_path.climb_target) || !wp_nav->set_wp_destination_next_loc(rtl_path.return_target)) {
// this should not happen because rtl_build_path will have checked terrain data was available
gcs().send_text(MAV_SEVERITY_CRITICAL,"RTL: unexpected error setting climb target");
gcs().send_text(MAV_SEVERITY_CRITICAL,"%s: unexpected error setting climb target", flightMode);
LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::FAILED_TO_SET_DESTINATION);
copter.set_mode(Mode::Number::LAND, ModeReason::TERRAIN_FAILSAFE);
return;
Expand Down Expand Up @@ -416,7 +416,7 @@ void ModeRTL::compute_return_target()
case AC_WPNav::TerrainSource::TERRAIN_UNAVAILABLE:
alt_type = ReturnTargetAltType::RELATIVE;
LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::RTL_MISSING_RNGFND);
gcs().send_text(MAV_SEVERITY_CRITICAL, "RTL: no terrain data, using alt-above-home");
gcs().send_text(MAV_SEVERITY_CRITICAL, "%s: no terrain data, using alt-above-home", flightMode);
break;
case AC_WPNav::TerrainSource::TERRAIN_FROM_RANGEFINDER:
alt_type = ReturnTargetAltType::RANGEFINDER;
Expand All @@ -435,7 +435,7 @@ void ModeRTL::compute_return_target()
} else {
// fallback to relative alt and warn user
alt_type = ReturnTargetAltType::RELATIVE;
gcs().send_text(MAV_SEVERITY_CRITICAL, "RTL: rangefinder unhealthy, using alt-above-home");
gcs().send_text(MAV_SEVERITY_CRITICAL, "%s: rangefinder unhealthy, using alt-above-home", flightMode);
LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::RTL_MISSING_RNGFND);
}
}
Expand All @@ -453,7 +453,7 @@ void ModeRTL::compute_return_target()
// fallback to relative alt and warn user
alt_type = ReturnTargetAltType::RELATIVE;
LOGGER_WRITE_ERROR(LogErrorSubsystem::TERRAIN, LogErrorCode::MISSING_TERRAIN_DATA);
gcs().send_text(MAV_SEVERITY_CRITICAL, "RTL: no terrain data, using alt-above-home");
gcs().send_text(MAV_SEVERITY_CRITICAL, "%s: no terrain data, using alt-above-home", flightMode);
}
}

Expand All @@ -462,7 +462,7 @@ void ModeRTL::compute_return_target()
if (!rtl_path.return_target.change_alt_frame(Location::AltFrame::ABOVE_HOME)) {
// this should never happen but just in case
rtl_path.return_target.set_alt_cm(0, Location::AltFrame::ABOVE_HOME);
gcs().send_text(MAV_SEVERITY_WARNING, "RTL: unexpected error calculating target alt");
gcs().send_text(MAV_SEVERITY_WARNING, "%s: unexpected error calculating target alt", flightMode);
}
}

Expand Down
7 changes: 4 additions & 3 deletions ArduCopter/mode_systemid.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -239,6 +239,7 @@ void ModeSystemId::run()
waveform_sample = chirp_input.update(waveform_time - SYSTEM_ID_DELAY, waveform_magnitude);
waveform_freq_rads = chirp_input.get_frequency_rads();
Vector2f disturb_state;
const char *strStoped = "SystemID Stopped";
switch (systemid_state) {
case SystemIDModeState::SYSTEMID_STATE_STOPPED:
attitude_control->bf_feedforward(att_bf_feedforward);
Expand All @@ -247,12 +248,12 @@ void ModeSystemId::run()

if (copter.ap.land_complete) {
systemid_state = SystemIDModeState::SYSTEMID_STATE_STOPPED;
gcs().send_text(MAV_SEVERITY_INFO, "SystemID Stopped: Landed");
gcs().send_text(MAV_SEVERITY_INFO, "%s: Landed", strStoped);
break;
}
if (attitude_control->lean_angle_deg()*100 > attitude_control->lean_angle_max_cd()) {
systemid_state = SystemIDModeState::SYSTEMID_STATE_STOPPED;
gcs().send_text(MAV_SEVERITY_INFO, "SystemID Stopped: lean=%f max=%f", (double)attitude_control->lean_angle_deg(), (double)attitude_control->lean_angle_max_cd());
gcs().send_text(MAV_SEVERITY_INFO, "%s: lean=%f max=%f", strStoped, (double)attitude_control->lean_angle_deg(), (double)attitude_control->lean_angle_max_cd());
break;
}
if (waveform_time > SYSTEM_ID_DELAY + time_fade_in + time_const_freq + time_record + time_fade_out) {
Expand All @@ -264,7 +265,7 @@ void ModeSystemId::run()
switch ((AxisType)axis.get()) {
case AxisType::NONE:
systemid_state = SystemIDModeState::SYSTEMID_STATE_STOPPED;
gcs().send_text(MAV_SEVERITY_INFO, "SystemID Stopped: axis = 0");
gcs().send_text(MAV_SEVERITY_INFO, "%s: axis = 0", strStoped);
break;
case AxisType::INPUT_ROLL:
target_roll += waveform_sample*100.0f;
Expand Down
2 changes: 0 additions & 2 deletions ArduCopter/mode_zigzag.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -227,7 +227,6 @@ void ModeZigZag::move_to_side()
current_dest = next_dest;
current_terr_alt = terr_alt;
reach_wp_time_ms = 0;
char const *dir[] = {"forward", "right", "backward", "left"};
gcs().send_text(MAV_SEVERITY_INFO, "%s: moving to %s", name(), dir[(uint8_t)zigzag_direction]);
}
}
Expand Down Expand Up @@ -549,7 +548,6 @@ void ModeZigZag::run_auto()
if (wp_nav->set_wp_destination(current_dest, current_terr_alt)) {
stage = AUTO;
reach_wp_time_ms = 0;
char const *dir[] = {"forward", "right", "backward", "left"};
gcs().send_text(MAV_SEVERITY_INFO, "%s: moving to %s", name(), dir[(uint8_t)zigzag_direction]);
}
}
Expand Down

0 comments on commit 3e43f62

Please sign in to comment.