Copter: revisions to text strings sent to GCS

This commit is contained in:
Luis Vale Gonçalves 2015-11-18 19:08:19 +00:00 committed by Randy Mackay
parent f5d73a9d10
commit 3199829d45
12 changed files with 37 additions and 37 deletions

View File

@ -43,15 +43,15 @@ void Copter::set_simple_mode(uint8_t b)
if(ap.simple_mode != b){
if(b == 0){
Log_Write_Event(DATA_SET_SIMPLE_OFF);
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Simple:OFF");
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "SIMPLE mode off");
}else if(b == 1){
Log_Write_Event(DATA_SET_SIMPLE_ON);
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Simple:ON");
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "SIMPLE mode on");
}else{
// initialise super simple heading
update_super_simple_bearing(true);
Log_Write_Event(DATA_SET_SUPERSIMPLE_ON);
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "SuperSimple:ON");
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "SUPERSIMPLE mode on");
}
ap.simple_mode = b;
}

View File

@ -1841,12 +1841,12 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
if (packet.idx >= copter.rally.get_rally_total() ||
packet.idx >= copter.rally.get_rally_max()) {
send_text(MAV_SEVERITY_NOTICE,"bad rally point message ID");
send_text(MAV_SEVERITY_NOTICE,"Bad rally point message ID");
break;
}
if (packet.count != copter.rally.get_rally_total()) {
send_text(MAV_SEVERITY_NOTICE,"bad rally point message count");
send_text(MAV_SEVERITY_NOTICE,"Bad rally point message count");
break;
}
@ -1859,7 +1859,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
rally_point.flags = packet.flags;
if (!copter.rally.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");
}
break;
@ -1875,7 +1875,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
//send_text(MAV_SEVERITY_INFO, "## getting rally point in GCS_Mavlink.cpp 2"); // #### TEMP
if (packet.idx > copter.rally.get_rally_total()) {
send_text(MAV_SEVERITY_NOTICE, "bad rally point index");
send_text(MAV_SEVERITY_NOTICE, "Bad rally point index");
break;
}
@ -1883,7 +1883,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
RallyLocation rally_point;
if (!copter.rally.get_rally_point_with_index(packet.idx, rally_point)) {
send_text(MAV_SEVERITY_NOTICE, "failed to set rally point");
send_text(MAV_SEVERITY_NOTICE, "Failed to set rally point");
break;
}
@ -1971,7 +1971,7 @@ 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");
}
check_usb_mux();

View File

@ -147,9 +147,9 @@ int8_t Copter::process_logs(uint8_t argc, const Menu::arg *argv)
void Copter::do_erase_logs(void)
{
gcs_send_text(MAV_SEVERITY_INFO, "Erasing logs\n");
gcs_send_text(MAV_SEVERITY_INFO, "Erasing logs");
DataFlash.EraseAll();
gcs_send_text(MAV_SEVERITY_INFO, "Log erase complete\n");
gcs_send_text(MAV_SEVERITY_INFO, "Log erase complete");
}
#if AUTOTUNE_ENABLED == ENABLED
@ -807,7 +807,7 @@ void Copter::log_init(void)
{
DataFlash.Init(log_structure, ARRAY_SIZE(log_structure));
if (!DataFlash.CardInserted()) {
gcs_send_text(MAV_SEVERITY_NOTICE, "No dataflash inserted");
gcs_send_text(MAV_SEVERITY_WARNING, "No dataflash card inserted");
g.log_bitmask.set(0);
} else if (DataFlash.NeedPrep()) {
gcs_send_text(MAV_SEVERITY_INFO, "Preparing log system");

View File

@ -610,7 +610,7 @@ bool Copter::verify_nav_wp(const AP_Mission::Mission_Command& cmd)
// check if timer has run out
if (((millis() - loiter_time) / 1000) >= loiter_time_max) {
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Reached Command #%i",cmd.index);
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Reached command #%i",cmd.index);
return true;
}else{
return false;
@ -692,7 +692,7 @@ bool Copter::verify_spline_wp(const AP_Mission::Mission_Command& cmd)
// check if timer has run out
if (((millis() - loiter_time) / 1000) >= loiter_time_max) {
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Reached Command #%i",cmd.index);
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Reached command #%i",cmd.index);
return true;
}else{
return false;

View File

@ -37,7 +37,7 @@ uint8_t Copter::mavlink_compassmot(mavlink_channel_t chan)
// check compass is enabled
if (!g.compass_enabled) {
gcs[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_CRITICAL, "compass disabled\n");
gcs[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_CRITICAL, "Compass disabled");
ap.compass_mot = false;
return 1;
}
@ -46,7 +46,7 @@ uint8_t Copter::mavlink_compassmot(mavlink_channel_t chan)
compass.read();
for (uint8_t i=0; i<compass.get_count(); i++) {
if (!compass.healthy(i)) {
gcs[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_CRITICAL, "check compass");
gcs[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_CRITICAL, "Check compass");
ap.compass_mot = false;
return 1;
}
@ -63,7 +63,7 @@ uint8_t Copter::mavlink_compassmot(mavlink_channel_t chan)
// check throttle is at zero
read_radio();
if (channel_throttle->control_in != 0) {
gcs[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_CRITICAL, "thr not zero");
gcs[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_CRITICAL, "Throttle not zero");
ap.compass_mot = false;
return 1;
}
@ -95,13 +95,13 @@ uint8_t Copter::mavlink_compassmot(mavlink_channel_t chan)
AP_Notify::flags.esc_calibration = true;
// warn user we are starting calibration
gcs[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_INFO, "STARTING CALIBRATION");
gcs[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_INFO, "Starting calibration");
// inform what type of compensation we are attempting
if (comp_type == AP_COMPASS_MOT_COMP_CURRENT) {
gcs[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_INFO, "CURRENT");
gcs[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_INFO, "Current");
} else{
gcs[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_INFO, "THROTTLE");
gcs[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_INFO, "Throttle");
}
// disable throttle and battery failsafe
@ -245,10 +245,10 @@ uint8_t Copter::mavlink_compassmot(mavlink_channel_t chan)
}
compass.save_motor_compensation();
// display success message
gcs[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_INFO, "Calibration Successful!");
gcs[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_INFO, "Calibration successful");
} else {
// compensation vector never updated, report failure
gcs[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_NOTICE, "Failed!");
gcs[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_NOTICE, "Failed");
compass.motor_compensation_type(AP_COMPASS_MOT_COMP_DISABLED);
}

View File

@ -243,7 +243,7 @@ bool Copter::autotune_start(bool ignore_checks)
return false;
}
// initialize vertical speeds and acceleration
// initialize vertical speeds and leash lengths
pos_control.set_speed_z(-g.pilot_velocity_z_max, g.pilot_velocity_z_max);
pos_control.set_accel_z(g.pilot_accel_z);
@ -1023,7 +1023,7 @@ void Copter::autotune_update_gcs(uint8_t message_id)
gcs_send_text(MAV_SEVERITY_NOTICE,"AutoTune: Failed");
break;
case AUTOTUNE_MESSAGE_SAVED_GAINS:
gcs_send_text(MAV_SEVERITY_INFO,"AutoTune: Saved Gains");
gcs_send_text(MAV_SEVERITY_INFO,"AutoTune: Saved gains");
break;
}
}

View File

@ -136,7 +136,7 @@ void Copter::parachute_check()
void Copter::parachute_release()
{
// send message to gcs and dataflash
gcs_send_text(MAV_SEVERITY_INFO,"Parachute: Released!");
gcs_send_text(MAV_SEVERITY_INFO,"Parachute: Released");
Log_Write_Event(DATA_PARACHUTE_RELEASED);
// disarm motors
@ -168,7 +168,7 @@ void Copter::parachute_manual_release()
// do not release if we are landed or below the minimum altitude above home
if ((parachute.alt_min() != 0 && (current_loc.alt < (int32_t)parachute.alt_min() * 100))) {
// warn user of reason for failure
gcs_send_text(MAV_SEVERITY_ALERT,"Parachute: Too Low");
gcs_send_text(MAV_SEVERITY_ALERT,"Parachute: Too low");
// log an error in the dataflash
Log_Write_Error(ERROR_SUBSYSTEM_PARACHUTE, ERROR_CODE_PARACHUTE_TOO_LOW);
return;

View File

@ -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(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
@ -85,7 +85,7 @@ void Copter::esc_calibration_passthrough()
motors.set_update_rate(50);
// send message to GCS
gcs_send_text(MAV_SEVERITY_INFO,"ESC Calibration: passing pilot throttle to ESCs");
gcs_send_text(MAV_SEVERITY_INFO,"ESC calibration: Passing pilot throttle to ESCs");
while(1) {
// arm motors
@ -115,7 +115,7 @@ void Copter::esc_calibration_auto()
motors.set_update_rate(50);
// send message to GCS
gcs_send_text(MAV_SEVERITY_INFO,"ESC Calibration: auto calibration");
gcs_send_text(MAV_SEVERITY_INFO,"ESC calibration: Auto calibration");
// arm and enable motors
motors.armed(true);
@ -131,7 +131,7 @@ void Copter::esc_calibration_auto()
// wait for safety switch to be pressed
while (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) {
if (!printed_msg) {
gcs_send_text(MAV_SEVERITY_INFO,"ESC Calibration: push safety switch");
gcs_send_text(MAV_SEVERITY_INFO,"ESC calibration: Push safety switch");
printed_msg = true;
}
delay(10);

View File

@ -159,7 +159,7 @@ void Copter::failsafe_battery_event(void)
set_failsafe_battery(true);
// warn the ground station and log to dataflash
gcs_send_text(MAV_SEVERITY_WARNING,"Low Battery!");
gcs_send_text(MAV_SEVERITY_WARNING,"Low battery");
Log_Write_Error(ERROR_SUBSYSTEM_FAILSAFE_BATT, ERROR_CODE_FAILSAFE_OCCURRED);
}

View File

@ -86,7 +86,7 @@ bool Copter::mavlink_motor_test_check(mavlink_channel_t chan, bool check_rc)
// check if safety switch has been pushed
if (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) {
gcs[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_CRITICAL,"Motor Test: Safety Switch");
gcs[chan-MAVLINK_COMM_0].send_text(MAV_SEVERITY_CRITICAL,"Motor Test: Safety switch");
return false;
}

View File

@ -153,7 +153,7 @@ bool Copter::init_arm_motors(bool arming_from_gcs)
}
#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
@ -848,7 +848,7 @@ void Copter::init_disarm_motors()
}
#if HIL_MODE != HIL_MODE_DISABLED || CONFIG_HAL_BOARD == HAL_BOARD_SITL
gcs_send_text(MAV_SEVERITY_INFO, "DISARMING MOTORS");
gcs_send_text(MAV_SEVERITY_INFO, "Disarming motors");
#endif
// save compass offsets learned by the EKF
@ -918,7 +918,7 @@ void Copter::lost_vehicle_check()
if (soundalarm_counter >= LOST_VEHICLE_DELAY) {
if (AP_Notify::flags.vehicle_lost == false) {
AP_Notify::flags.vehicle_lost = true;
gcs_send_text(MAV_SEVERITY_NOTICE,"Locate Copter Alarm!");
gcs_send_text(MAV_SEVERITY_NOTICE,"Locate Copter alarm");
}
} else {
soundalarm_counter++;

View File

@ -4,13 +4,13 @@
void Copter::init_barometer(bool full_calibration)
{
gcs_send_text(MAV_SEVERITY_NOTICE, "Calibrating barometer");
gcs_send_text(MAV_SEVERITY_INFO, "Calibrating barometer");
if (full_calibration) {
barometer.calibrate();
}else{
barometer.update_calibration();
}
gcs_send_text(MAV_SEVERITY_INFO, "barometer calibration complete");
gcs_send_text(MAV_SEVERITY_INFO, "Barometer calibration complete");
}
// return barometric altitude in centimeters