Rename gcs_send_text_P to gcs_send_text

This commit is contained in:
Lucas De Marchi 2015-10-24 20:36:35 -02:00 committed by Randy Mackay
parent a8455aa4e3
commit 84da1f5039
41 changed files with 166 additions and 166 deletions

View File

@ -1366,7 +1366,7 @@ void Rover::mavlink_delay_cb()
}
if (tnow - last_5s > 5000) {
last_5s = tnow;
gcs_send_text_P(MAV_SEVERITY_WARNING, "Initialising APM...");
gcs_send_text(MAV_SEVERITY_WARNING, "Initialising APM...");
}
check_usb_mux();
@ -1426,7 +1426,7 @@ void Rover::gcs_update(void)
}
}
void Rover::gcs_send_text_P(MAV_SEVERITY severity, const prog_char_t *str)
void Rover::gcs_send_text(MAV_SEVERITY severity, const prog_char_t *str)
{
for (uint8_t i=0; i<num_gcs; i++) {
if (gcs[i].initialised) {

View File

@ -391,12 +391,12 @@ void Rover::log_init(void)
{
DataFlash.Init(log_structure, ARRAY_SIZE(log_structure));
if (!DataFlash.CardInserted()) {
gcs_send_text_P(MAV_SEVERITY_WARNING, "No dataflash card inserted");
gcs_send_text(MAV_SEVERITY_WARNING, "No dataflash card inserted");
g.log_bitmask.set(0);
} else if (DataFlash.NeedPrep()) {
gcs_send_text_P(MAV_SEVERITY_WARNING, "Preparing log system");
gcs_send_text(MAV_SEVERITY_WARNING, "Preparing log system");
DataFlash.Prep();
gcs_send_text_P(MAV_SEVERITY_WARNING, "Prepared log system");
gcs_send_text(MAV_SEVERITY_WARNING, "Prepared log system");
for (uint8_t i=0; i<num_gcs; i++) {
gcs[i].reset_cli_timeout();
}

View File

@ -399,7 +399,7 @@ private:
void gcs_send_mission_item_reached_message(uint16_t mission_index);
void gcs_data_stream_send(void);
void gcs_update(void);
void gcs_send_text_P(MAV_SEVERITY severity, const prog_char_t *str);
void gcs_send_text(MAV_SEVERITY severity, const prog_char_t *str);
void gcs_retry_deferred(void);
void do_erase_logs(void);

View File

@ -31,7 +31,7 @@ bool Rover::auto_check_trigger(void)
// check for user pressing the auto trigger to off
if (auto_triggered && g.auto_trigger_pin != -1 && check_digital_pin(g.auto_trigger_pin) == 1) {
gcs_send_text_P(MAV_SEVERITY_WARNING, "AUTO triggered off");
gcs_send_text(MAV_SEVERITY_WARNING, "AUTO triggered off");
auto_triggered = false;
return false;
}
@ -49,7 +49,7 @@ bool Rover::auto_check_trigger(void)
}
if (g.auto_trigger_pin != -1 && check_digital_pin(g.auto_trigger_pin) == 0) {
gcs_send_text_P(MAV_SEVERITY_WARNING, "Triggered AUTO with pin");
gcs_send_text(MAV_SEVERITY_WARNING, "Triggered AUTO with pin");
auto_triggered = true;
return true;
}

View File

@ -30,7 +30,7 @@ void Rover::set_next_WP(const struct Location& loc)
// location as the previous waypoint, to prevent immediately
// considering the waypoint complete
if (location_passed_point(current_loc, prev_WP, next_WP)) {
gcs_send_text_P(MAV_SEVERITY_WARNING, "Resetting prev_WP");
gcs_send_text(MAV_SEVERITY_WARNING, "Resetting prev_WP");
prev_WP = current_loc;
}
@ -63,7 +63,7 @@ void Rover::init_home()
return;
}
gcs_send_text_P(MAV_SEVERITY_WARNING, "init home");
gcs_send_text(MAV_SEVERITY_WARNING, "init home");
ahrs.set_home(gps.location());
home_is_set = true;

View File

@ -164,7 +164,7 @@ bool Rover::verify_command(const AP_Mission::Mission_Command& cmd)
// this is a command that doesn't require verify
return true;
}
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"verify_conditon: Unsupported command");
gcs_send_text(MAV_SEVERITY_CRITICAL,"verify_conditon: Unsupported command");
return true;
}
return false;
@ -248,7 +248,7 @@ bool Rover::verify_nav_wp(const AP_Mission::Mission_Command& cmd)
bool Rover::verify_RTL()
{
if (wp_distance <= g.waypoint_radius) {
gcs_send_text_P(MAV_SEVERITY_WARNING,"Reached Destination");
gcs_send_text(MAV_SEVERITY_WARNING,"Reached Destination");
rtl_complete = true;
return true;
}

View File

@ -22,7 +22,7 @@ void Rover::navigate()
wp_distance = get_distance(current_loc, next_WP);
if (wp_distance < 0){
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"<navigate> WP error - distance < 0");
gcs_send_text(MAV_SEVERITY_CRITICAL,"<navigate> WP error - distance < 0");
return;
}

View File

@ -4,9 +4,9 @@
void Rover::init_barometer(void)
{
gcs_send_text_P(MAV_SEVERITY_WARNING, "Calibrating barometer");
gcs_send_text(MAV_SEVERITY_WARNING, "Calibrating barometer");
barometer.calibrate();
gcs_send_text_P(MAV_SEVERITY_WARNING, "barometer calibration complete");
gcs_send_text(MAV_SEVERITY_WARNING, "barometer calibration complete");
}
void Rover::init_sonar(void)

View File

@ -226,10 +226,10 @@ void Rover::startup_ground(void)
{
set_mode(INITIALISING);
gcs_send_text_P(MAV_SEVERITY_WARNING,"<startup_ground> GROUND START");
gcs_send_text(MAV_SEVERITY_WARNING,"<startup_ground> GROUND START");
#if(GROUND_START_DELAY > 0)
gcs_send_text_P(MAV_SEVERITY_WARNING,"<startup_ground> With Delay");
gcs_send_text(MAV_SEVERITY_WARNING,"<startup_ground> With Delay");
delay(GROUND_START_DELAY * 1000);
#endif
@ -253,7 +253,7 @@ void Rover::startup_ground(void)
ins.set_raw_logging(should_log(MASK_LOG_IMU_RAW));
ins.set_dataflash(&DataFlash);
gcs_send_text_P(MAV_SEVERITY_WARNING,"\n\n Ready to drive.");
gcs_send_text(MAV_SEVERITY_WARNING,"\n\n Ready to drive.");
}
/*
@ -391,12 +391,12 @@ void Rover::failsafe_trigger(uint8_t failsafe_type, bool on)
void Rover::startup_INS_ground(void)
{
gcs_send_text_P(MAV_SEVERITY_ALERT, "Warming up ADC...");
gcs_send_text(MAV_SEVERITY_ALERT, "Warming up ADC...");
mavlink_delay(500);
// Makes the servos wiggle twice - about to begin INS calibration - HOLD LEVEL AND STILL!!
// -----------------------
gcs_send_text_P(MAV_SEVERITY_ALERT, "Beginning INS calibration; do not move vehicle");
gcs_send_text(MAV_SEVERITY_ALERT, "Beginning INS calibration; do not move vehicle");
mavlink_delay(1000);
ahrs.init();

View File

@ -919,7 +919,7 @@ void Tracker::mavlink_delay_cb()
}
if (tnow - last_5s > 5000) {
last_5s = tnow;
gcs_send_text_P(MAV_SEVERITY_WARNING, "Initialising APM...");
gcs_send_text(MAV_SEVERITY_WARNING, "Initialising APM...");
}
in_mavlink_delay = false;
}
@ -960,7 +960,7 @@ void Tracker::gcs_update(void)
}
}
void Tracker::gcs_send_text_P(MAV_SEVERITY severity, const prog_char_t *str)
void Tracker::gcs_send_text(MAV_SEVERITY severity, const prog_char_t *str)
{
for (uint8_t i=0; i<num_gcs; i++) {
if (gcs[i].initialised) {

View File

@ -202,7 +202,7 @@ private:
void gcs_send_message(enum ap_message id);
void gcs_data_stream_send(void);
void gcs_update(void);
void gcs_send_text_P(MAV_SEVERITY severity, const prog_char_t *str);
void gcs_send_text(MAV_SEVERITY severity, const prog_char_t *str);
void gcs_retry_deferred(void);
void load_parameters(void);
void update_auto(void);

View File

@ -4,9 +4,9 @@
void Tracker::init_barometer(void)
{
gcs_send_text_P(MAV_SEVERITY_WARNING, "Calibrating barometer");
gcs_send_text(MAV_SEVERITY_WARNING, "Calibrating barometer");
barometer.calibrate();
gcs_send_text_P(MAV_SEVERITY_WARNING, "barometer calibration complete");
gcs_send_text(MAV_SEVERITY_WARNING, "barometer calibration complete");
}
// read the barometer and return the updated altitude in meters

View File

@ -98,7 +98,7 @@ void Tracker::init_tracker()
if (fabsf(g.start_latitude) <= 90.0f && fabsf(g.start_longitude) <= 180.0f) {
current_loc.lat = g.start_latitude * 1.0e7f;
current_loc.lng = g.start_longitude * 1.0e7f;
gcs_send_text_P(MAV_SEVERITY_WARNING, "ignoring invalid START_LATITUDE or START_LONGITUDE parameter");
gcs_send_text(MAV_SEVERITY_WARNING, "ignoring invalid START_LATITUDE or START_LONGITUDE parameter");
}
// see if EEPROM has a default location as well
@ -108,7 +108,7 @@ void Tracker::init_tracker()
init_capabilities();
gcs_send_text_P(MAV_SEVERITY_WARNING,"\nReady to track.");
gcs_send_text(MAV_SEVERITY_WARNING,"\nReady to track.");
hal.scheduler->delay(1000); // Why????
set_mode(AUTO); // tracking

View File

@ -610,7 +610,7 @@ private:
void gcs_send_mission_item_reached_message(uint16_t mission_index);
void gcs_data_stream_send(void);
void gcs_check_input(void);
void gcs_send_text_P(MAV_SEVERITY severity, const prog_char_t *str);
void gcs_send_text(MAV_SEVERITY severity, const prog_char_t *str);
void do_erase_logs(void);
void Log_Write_AutoTune(uint8_t axis, uint8_t tune_step, float meas_target, float meas_min, float meas_max, float new_gain_rp, float new_gain_rd, float new_gain_sp, float new_ddt);
void Log_Write_AutoTuneDetails(float angle_cd, float rate_cds);

View File

@ -1970,7 +1970,7 @@ void Copter::mavlink_delay_cb()
}
if (tnow - last_5s > 5000) {
last_5s = tnow;
gcs_send_text_P(MAV_SEVERITY_WARNING, "Initialising APM...");
gcs_send_text(MAV_SEVERITY_WARNING, "Initialising APM...");
}
check_usb_mux();
@ -2030,7 +2030,7 @@ void Copter::gcs_check_input(void)
}
}
void Copter::gcs_send_text_P(MAV_SEVERITY severity, const prog_char_t *str)
void Copter::gcs_send_text(MAV_SEVERITY severity, const prog_char_t *str)
{
for (uint8_t i=0; i<num_gcs; i++) {
if (gcs[i].initialised) {

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_P(MAV_SEVERITY_CRITICAL, "Erasing logs\n");
gcs_send_text(MAV_SEVERITY_CRITICAL, "Erasing logs\n");
DataFlash.EraseAll();
gcs_send_text_P(MAV_SEVERITY_CRITICAL, "Log erase complete\n");
gcs_send_text(MAV_SEVERITY_CRITICAL, "Log erase complete\n");
}
#if AUTOTUNE_ENABLED == ENABLED
@ -807,12 +807,12 @@ void Copter::log_init(void)
{
DataFlash.Init(log_structure, ARRAY_SIZE(log_structure));
if (!DataFlash.CardInserted()) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL, "No dataflash inserted");
gcs_send_text(MAV_SEVERITY_CRITICAL, "No dataflash inserted");
g.log_bitmask.set(0);
} else if (DataFlash.NeedPrep()) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL, "Preparing log system");
gcs_send_text(MAV_SEVERITY_CRITICAL, "Preparing log system");
DataFlash.Prep();
gcs_send_text_P(MAV_SEVERITY_CRITICAL, "Prepared log system");
gcs_send_text(MAV_SEVERITY_CRITICAL, "Prepared log system");
for (uint8_t i=0; i<num_gcs; i++) {
gcs[i].reset_cli_timeout();
}

View File

@ -1007,19 +1007,19 @@ void Copter::autotune_update_gcs(uint8_t message_id)
{
switch (message_id) {
case AUTOTUNE_MESSAGE_STARTED:
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"AutoTune: Started");
gcs_send_text(MAV_SEVERITY_CRITICAL,"AutoTune: Started");
break;
case AUTOTUNE_MESSAGE_STOPPED:
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"AutoTune: Stopped");
gcs_send_text(MAV_SEVERITY_CRITICAL,"AutoTune: Stopped");
break;
case AUTOTUNE_MESSAGE_SUCCESS:
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"AutoTune: Success");
gcs_send_text(MAV_SEVERITY_CRITICAL,"AutoTune: Success");
break;
case AUTOTUNE_MESSAGE_FAILED:
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"AutoTune: Failed");
gcs_send_text(MAV_SEVERITY_CRITICAL,"AutoTune: Failed");
break;
case AUTOTUNE_MESSAGE_SAVED_GAINS:
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"AutoTune: Saved Gains");
gcs_send_text(MAV_SEVERITY_CRITICAL,"AutoTune: Saved Gains");
break;
}
}

View File

@ -47,7 +47,7 @@ void Copter::crash_check()
// log an error in the dataflash
Log_Write_Error(ERROR_SUBSYSTEM_CRASH_CHECK, ERROR_CODE_CRASH_CHECK_CRASH);
// send message to gcs
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Crash: Disarming");
gcs_send_text(MAV_SEVERITY_CRITICAL,"Crash: Disarming");
// disarm motors
init_disarm_motors();
}
@ -136,7 +136,7 @@ void Copter::parachute_check()
void Copter::parachute_release()
{
// send message to gcs and dataflash
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Parachute: Released!");
gcs_send_text(MAV_SEVERITY_CRITICAL,"Parachute: Released!");
Log_Write_Event(DATA_PARACHUTE_RELEASED);
// disarm motors
@ -159,7 +159,7 @@ void Copter::parachute_manual_release()
// do not release if we are landed or below the minimum altitude above home
if (ap.land_complete) {
// warn user of reason for failure
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Parachute: Landed");
gcs_send_text(MAV_SEVERITY_CRITICAL,"Parachute: Landed");
// log an error in the dataflash
Log_Write_Error(ERROR_SUBSYSTEM_PARACHUTE, ERROR_CODE_PARACHUTE_LANDED);
return;
@ -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_P(MAV_SEVERITY_CRITICAL,"Parachute: Too Low");
gcs_send_text(MAV_SEVERITY_CRITICAL,"Parachute: Too Low");
// log an error in the dataflash
Log_Write_Error(ERROR_SUBSYSTEM_PARACHUTE, ERROR_CODE_PARACHUTE_TOO_LOW);
return;

View File

@ -60,7 +60,7 @@ void Copter::ekf_check()
Log_Write_Error(ERROR_SUBSYSTEM_EKFCHECK, ERROR_CODE_EKFCHECK_BAD_VARIANCE);
// send message to gcs
if ((hal.scheduler->millis() - ekf_check_state.last_warn_time) > EKF_CHECK_WARNING_TIME) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"EKF variance");
gcs_send_text(MAV_SEVERITY_CRITICAL,"EKF variance");
ekf_check_state.last_warn_time = hal.scheduler->millis();
}
failsafe_ekf_event();

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_P(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_P(MAV_SEVERITY_CRITICAL,"ESC Calibration: passing pilot throttle to ESCs");
gcs_send_text(MAV_SEVERITY_CRITICAL,"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_P(MAV_SEVERITY_CRITICAL,"ESC Calibration: auto calibration");
gcs_send_text(MAV_SEVERITY_CRITICAL,"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_P(MAV_SEVERITY_CRITICAL,"ESC Calibration: push safety switch");
gcs_send_text(MAV_SEVERITY_CRITICAL,"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_P(MAV_SEVERITY_CRITICAL,"Low Battery!");
gcs_send_text(MAV_SEVERITY_CRITICAL,"Low Battery!");
Log_Write_Error(ERROR_SUBSYSTEM_FAILSAFE_BATT, ERROR_CODE_FAILSAFE_OCCURRED);
}

View File

@ -149,7 +149,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_P(MAV_SEVERITY_CRITICAL, "ARMING MOTORS");
gcs_send_text(MAV_SEVERITY_CRITICAL, "ARMING MOTORS");
#endif
// Remember Orientation
@ -178,7 +178,7 @@ bool Copter::init_arm_motors(bool arming_from_gcs)
// if we are using motor interlock switch and it's enabled, fail to arm
if (ap.using_interlock && motors.get_interlock()){
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Arm: Motor Interlock Enabled");
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Motor Interlock Enabled");
AP_Notify::flags.armed = false;
in_arm_motors = false;
return false;
@ -190,7 +190,7 @@ bool Copter::init_arm_motors(bool arming_from_gcs)
set_motor_emergency_stop(false);
// if we are using motor Estop switch, it must not be in Estop position
} else if (check_if_auxsw_mode_used(AUXSW_MOTOR_ESTOP) && ap.motor_emergency_stop){
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Arm: Motor Emergency Stopped");
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Motor Emergency Stopped");
AP_Notify::flags.armed = false;
in_arm_motors = false;
return false;
@ -246,7 +246,7 @@ bool Copter::pre_arm_checks(bool display_failure)
// at the same time. This cannot be allowed.
if (check_if_auxsw_mode_used(AUXSW_MOTOR_INTERLOCK) && check_if_auxsw_mode_used(AUXSW_MOTOR_ESTOP)){
if (display_failure) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: Interlock/E-Stop Conflict");
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Interlock/E-Stop Conflict");
}
return false;
}
@ -258,7 +258,7 @@ bool Copter::pre_arm_checks(bool display_failure)
set_using_interlock(check_if_auxsw_mode_used(AUXSW_MOTOR_INTERLOCK));
if (ap.using_interlock && motors.get_interlock()){
if (display_failure) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: Motor Interlock Enabled");
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Motor Interlock Enabled");
}
return false;
}
@ -267,7 +267,7 @@ bool Copter::pre_arm_checks(bool display_failure)
// and warn if it is
if (check_if_auxsw_mode_used(AUXSW_MOTOR_ESTOP) && ap.motor_emergency_stop){
if (display_failure) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: Motor Emergency Stopped");
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Motor Emergency Stopped");
}
return false;
}
@ -291,7 +291,7 @@ bool Copter::pre_arm_checks(bool display_failure)
pre_arm_rc_checks();
if(!ap.pre_arm_rc_check) {
if (display_failure) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: RC not calibrated");
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: RC not calibrated");
}
return false;
}
@ -300,7 +300,7 @@ bool Copter::pre_arm_checks(bool display_failure)
// barometer health check
if(!barometer.all_healthy()) {
if (display_failure) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: Barometer not healthy");
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Barometer not healthy");
}
return false;
}
@ -312,7 +312,7 @@ bool Copter::pre_arm_checks(bool display_failure)
if (using_baro_ref) {
if (fabsf(inertial_nav.get_altitude() - baro_alt) > PREARM_MAX_ALT_DISPARITY_CM) {
if (display_failure) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: Altitude disparity");
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Altitude disparity");
}
return false;
}
@ -324,7 +324,7 @@ bool Copter::pre_arm_checks(bool display_failure)
// check the primary compass is healthy
if(!compass.healthy()) {
if (display_failure) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: Compass not healthy");
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Compass not healthy");
}
return false;
}
@ -332,7 +332,7 @@ bool Copter::pre_arm_checks(bool display_failure)
// check compass learning is on or offsets have been set
if(!compass.configured()) {
if (display_failure) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: Compass not calibrated");
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Compass not calibrated");
}
return false;
}
@ -341,7 +341,7 @@ bool Copter::pre_arm_checks(bool display_failure)
Vector3f offsets = compass.get_offsets();
if(offsets.length() > COMPASS_OFFSETS_MAX) {
if (display_failure) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: Compass offsets too high");
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Compass offsets too high");
}
return false;
}
@ -350,7 +350,7 @@ bool Copter::pre_arm_checks(bool display_failure)
float mag_field = compass.get_field().length();
if (mag_field > COMPASS_MAGFIELD_EXPECTED*1.65f || mag_field < COMPASS_MAGFIELD_EXPECTED*0.35f) {
if (display_failure) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: Check mag field");
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Check mag field");
}
return false;
}
@ -358,7 +358,7 @@ bool Copter::pre_arm_checks(bool display_failure)
// check all compasses point in roughly same direction
if (!compass.consistent()) {
if (display_failure) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: inconsistent compasses");
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: inconsistent compasses");
}
return false;
}
@ -374,7 +374,7 @@ bool Copter::pre_arm_checks(bool display_failure)
// check fence is initialised
if(!fence.pre_arm_check()) {
if (display_failure) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: check fence");
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: check fence");
}
return false;
}
@ -385,7 +385,7 @@ bool Copter::pre_arm_checks(bool display_failure)
// check accelerometers have been calibrated
if(!ins.accel_calibrated_ok_all()) {
if (display_failure) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: Accels not calibrated");
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Accels not calibrated");
}
return false;
}
@ -393,7 +393,7 @@ bool Copter::pre_arm_checks(bool display_failure)
// check accels are healthy
if(!ins.get_accel_health_all()) {
if (display_failure) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: Accelerometers not healthy");
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Accelerometers not healthy");
}
return false;
}
@ -416,7 +416,7 @@ bool Copter::pre_arm_checks(bool display_failure)
}
if (vec_diff.length() > threshold) {
if (display_failure) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: inconsistent Accelerometers");
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: inconsistent Accelerometers");
}
return false;
}
@ -426,7 +426,7 @@ bool Copter::pre_arm_checks(bool display_failure)
// check gyros are healthy
if(!ins.get_gyro_health_all()) {
if (display_failure) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: Gyros not healthy");
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Gyros not healthy");
}
return false;
}
@ -438,7 +438,7 @@ bool Copter::pre_arm_checks(bool display_failure)
Vector3f vec_diff = ins.get_gyro(i) - ins.get_gyro();
if (vec_diff.length() > PREARM_MAX_GYRO_VECTOR_DIFF) {
if (display_failure) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: inconsistent Gyros");
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: inconsistent Gyros");
}
return false;
}
@ -448,7 +448,7 @@ bool Copter::pre_arm_checks(bool display_failure)
// get ekf attitude (if bad, it's usually the gyro biases)
if (!pre_arm_ekf_attitude_check()) {
if (display_failure) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: gyros still settling");
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: gyros still settling");
}
return false;
}
@ -459,7 +459,7 @@ bool Copter::pre_arm_checks(bool display_failure)
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_VOLTAGE)) {
if(hal.analogin->board_voltage() < BOARD_VOLTAGE_MIN || hal.analogin->board_voltage() > BOARD_VOLTAGE_MAX) {
if (display_failure) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: Check Board Voltage");
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Check Board Voltage");
}
return false;
}
@ -471,7 +471,7 @@ bool Copter::pre_arm_checks(bool display_failure)
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_VOLTAGE)) {
if (failsafe.battery || (!ap.usb_connected && battery.exhausted(g.fs_batt_voltage, g.fs_batt_mah))) {
if (display_failure) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: Check Battery");
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Check Battery");
}
return false;
}
@ -483,7 +483,7 @@ bool Copter::pre_arm_checks(bool display_failure)
// ensure ch7 and ch8 have different functions
if (check_duplicate_auxsw()) {
if (display_failure) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: Duplicate Aux Switch Options");
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Duplicate Aux Switch Options");
}
return false;
}
@ -493,7 +493,7 @@ bool Copter::pre_arm_checks(bool display_failure)
// check throttle min is above throttle failsafe trigger and that the trigger is above ppm encoder's loss-of-signal value of 900
if (channel_throttle->radio_min <= g.failsafe_throttle_value+10 || g.failsafe_throttle_value < 910) {
if (display_failure) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: Check FS_THR_VALUE");
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Check FS_THR_VALUE");
}
return false;
}
@ -502,7 +502,7 @@ bool Copter::pre_arm_checks(bool display_failure)
// lean angle parameter check
if (aparm.angle_max < 1000 || aparm.angle_max > 8000) {
if (display_failure) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: Check ANGLE_MAX");
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Check ANGLE_MAX");
}
return false;
}
@ -510,7 +510,7 @@ bool Copter::pre_arm_checks(bool display_failure)
// acro balance parameter check
if ((g.acro_balance_roll > g.p_stabilize_roll.kP()) || (g.acro_balance_pitch > g.p_stabilize_pitch.kP())) {
if (display_failure) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: ACRO_BAL_ROLL/PITCH");
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: ACRO_BAL_ROLL/PITCH");
}
return false;
}
@ -519,7 +519,7 @@ bool Copter::pre_arm_checks(bool display_failure)
// check range finder if optflow enabled
if (optflow.enabled() && !sonar.pre_arm_check()) {
if (display_failure) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: check range finder");
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: check range finder");
}
return false;
}
@ -538,9 +538,9 @@ bool Copter::pre_arm_checks(bool display_failure)
if (g.failsafe_throttle != FS_THR_DISABLED && channel_throttle->radio_in < g.failsafe_throttle_value) {
if (display_failure) {
#if FRAME_CONFIG == HELI_FRAME
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: Collective below Failsafe");
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Collective below Failsafe");
#else
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: Throttle below Failsafe");
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Throttle below Failsafe");
#endif
}
return false;
@ -601,7 +601,7 @@ bool Copter::pre_arm_gps_checks(bool display_failure)
// always check if inertial nav has started and is ready
if(!ahrs.healthy()) {
if (display_failure) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: Waiting for Nav Checks");
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Waiting for Nav Checks");
}
return false;
}
@ -629,7 +629,7 @@ bool Copter::pre_arm_gps_checks(bool display_failure)
if (reason) {
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: %s", reason);
} else {
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: Need 3D Fix");
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Need 3D Fix");
}
}
AP_Notify::flags.pre_arm_gps_check = false;
@ -643,7 +643,7 @@ bool Copter::pre_arm_gps_checks(bool display_failure)
ahrs.get_variances(vel_variance, pos_variance, hgt_variance, mag_variance, tas_variance, offset);
if (mag_variance.length() >= g.fs_ekf_thresh) {
if (display_failure) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: EKF compass variance");
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: EKF compass variance");
}
return false;
}
@ -651,7 +651,7 @@ bool Copter::pre_arm_gps_checks(bool display_failure)
// check home and EKF origin are not too far
if (far_from_EKF_origin(ahrs.get_home())) {
if (display_failure) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: EKF-home variance");
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: EKF-home variance");
}
AP_Notify::flags.pre_arm_gps_check = false;
return false;
@ -666,7 +666,7 @@ bool Copter::pre_arm_gps_checks(bool display_failure)
// warn about hdop separately - to prevent user confusion with no gps lock
if (gps.get_hdop() > g.gps_hdop_good) {
if (display_failure) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"PreArm: High GPS HDOP");
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: High GPS HDOP");
}
AP_Notify::flags.pre_arm_gps_check = false;
return false;
@ -700,20 +700,20 @@ bool Copter::arm_checks(bool display_failure, bool arming_from_gcs)
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_INS)) {
if(!ins.get_accel_health_all()) {
if (display_failure) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Arm: Accelerometers not healthy");
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Accelerometers not healthy");
}
return false;
}
if(!ins.get_gyro_health_all()) {
if (display_failure) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Arm: Gyros not healthy");
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Gyros not healthy");
}
return false;
}
// get ekf attitude (if bad, it's usually the gyro biases)
if (!pre_arm_ekf_attitude_check()) {
if (display_failure) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Arm: gyros still settling");
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: gyros still settling");
}
return false;
}
@ -722,14 +722,14 @@ bool Copter::arm_checks(bool display_failure, bool arming_from_gcs)
// always check if inertial nav has started and is ready
if(!ahrs.healthy()) {
if (display_failure) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Arm: Waiting for Nav Checks");
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Waiting for Nav Checks");
}
return false;
}
if(compass.is_calibrating()) {
if (display_failure) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Arm: Compass calibration running");
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Compass calibration running");
}
return false;
}
@ -737,7 +737,7 @@ bool Copter::arm_checks(bool display_failure, bool arming_from_gcs)
// always check if the current mode allows arming
if (!mode_allows_arming(control_mode, arming_from_gcs)) {
if (display_failure) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Arm: Mode not armable");
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Mode not armable");
}
return false;
}
@ -757,7 +757,7 @@ bool Copter::arm_checks(bool display_failure, bool arming_from_gcs)
// baro health check
if (!barometer.all_healthy()) {
if (display_failure) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Arm: Barometer not healthy");
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Barometer not healthy");
}
return false;
}
@ -768,7 +768,7 @@ bool Copter::arm_checks(bool display_failure, bool arming_from_gcs)
bool using_baro_ref = (!filt_status.flags.pred_horiz_pos_rel && filt_status.flags.pred_horiz_pos_abs);
if (using_baro_ref && (fabsf(inertial_nav.get_altitude() - baro_alt) > PREARM_MAX_ALT_DISPARITY_CM)) {
if (display_failure) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Arm: Altitude disparity");
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Altitude disparity");
}
return false;
}
@ -778,7 +778,7 @@ bool Copter::arm_checks(bool display_failure, bool arming_from_gcs)
// check vehicle is within fence
if(!fence.pre_arm_check()) {
if (display_failure) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Arm: check fence");
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: check fence");
}
return false;
}
@ -788,7 +788,7 @@ bool Copter::arm_checks(bool display_failure, bool arming_from_gcs)
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_INS)) {
if (degrees(acosf(ahrs.cos_roll()*ahrs.cos_pitch()))*100.0f > aparm.angle_max) {
if (display_failure) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Arm: Leaning");
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Leaning");
}
return false;
}
@ -798,7 +798,7 @@ bool Copter::arm_checks(bool display_failure, bool arming_from_gcs)
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_VOLTAGE)) {
if (failsafe.battery || (!ap.usb_connected && battery.exhausted(g.fs_batt_voltage, g.fs_batt_mah))) {
if (display_failure) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Arm: Check Battery");
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Check Battery");
}
return false;
}
@ -810,9 +810,9 @@ bool Copter::arm_checks(bool display_failure, bool arming_from_gcs)
if (g.failsafe_throttle != FS_THR_DISABLED && channel_throttle->radio_in < g.failsafe_throttle_value) {
if (display_failure) {
#if FRAME_CONFIG == HELI_FRAME
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Arm: Collective below Failsafe");
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Collective below Failsafe");
#else
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Arm: Throttle below Failsafe");
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Throttle below Failsafe");
#endif
}
return false;
@ -824,9 +824,9 @@ bool Copter::arm_checks(bool display_failure, bool arming_from_gcs)
if (channel_throttle->control_in > get_takeoff_trigger_throttle()) {
if (display_failure) {
#if FRAME_CONFIG == HELI_FRAME
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Arm: Collective too high");
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Collective too high");
#else
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Arm: Throttle too high");
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Throttle too high");
#endif
}
return false;
@ -835,9 +835,9 @@ bool Copter::arm_checks(bool display_failure, bool arming_from_gcs)
if ((mode_has_manual_throttle(control_mode) || control_mode == DRIFT) && channel_throttle->control_in > 0) {
if (display_failure) {
#if FRAME_CONFIG == HELI_FRAME
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Arm: Collective too high");
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Collective too high");
#else
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Arm: Throttle too high");
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Throttle too high");
#endif
}
return false;
@ -848,7 +848,7 @@ bool Copter::arm_checks(bool display_failure, bool arming_from_gcs)
// check if safety switch has been pushed
if (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) {
if (display_failure) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Arm: Safety Switch");
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Safety Switch");
}
return false;
}
@ -866,7 +866,7 @@ void Copter::init_disarm_motors()
}
#if HIL_MODE != HIL_MODE_DISABLED || CONFIG_HAL_BOARD == HAL_BOARD_SITL
gcs_send_text_P(MAV_SEVERITY_CRITICAL, "DISARMING MOTORS");
gcs_send_text(MAV_SEVERITY_CRITICAL, "DISARMING MOTORS");
#endif
// save compass offsets learned by the EKF
@ -936,7 +936,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_P(MAV_SEVERITY_CRITICAL,"Locate Copter Alarm!");
gcs_send_text(MAV_SEVERITY_CRITICAL,"Locate Copter Alarm!");
}
} else {
soundalarm_counter++;

View File

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

View File

@ -597,7 +597,7 @@ void Copter::save_trim()
float pitch_trim = ToRad((float)channel_pitch->control_in/100.0f);
ahrs.add_trim(roll_trim, pitch_trim);
Log_Write_Event(DATA_SAVE_TRIM);
gcs_send_text_P(MAV_SEVERITY_CRITICAL, "Trim saved");
gcs_send_text(MAV_SEVERITY_CRITICAL, "Trim saved");
}
// auto_trim - slightly adjusts the ahrs.roll_trim and ahrs.pitch_trim towards the current stick positions

View File

@ -234,7 +234,7 @@ void Copter::init_ardupilot()
while (barometer.get_last_update() == 0) {
// the barometer begins updating when we get the first
// HIL_STATE message
gcs_send_text_P(MAV_SEVERITY_WARNING, "Waiting for first HIL_STATE message");
gcs_send_text(MAV_SEVERITY_WARNING, "Waiting for first HIL_STATE message");
delay(1000);
}

View File

@ -635,7 +635,7 @@ void Plane::update_flight_mode(void)
if (tdrag_mode && !auto_state.fbwa_tdrag_takeoff_mode) {
if (auto_state.highest_airspeed < g.takeoff_tdrag_speed1) {
auto_state.fbwa_tdrag_takeoff_mode = true;
gcs_send_text_P(MAV_SEVERITY_WARNING, "FBWA tdrag mode\n");
gcs_send_text(MAV_SEVERITY_WARNING, "FBWA tdrag mode\n");
}
}
}
@ -781,15 +781,15 @@ void Plane::set_flight_stage(AP_SpdHgtControl::FlightStage fs)
#if GEOFENCE_ENABLED == ENABLED
if (g.fence_autoenable == 1) {
if (! geofence_set_enabled(false, AUTO_TOGGLED)) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL, "Disable fence failed (autodisable)");
gcs_send_text(MAV_SEVERITY_CRITICAL, "Disable fence failed (autodisable)");
} else {
gcs_send_text_P(MAV_SEVERITY_CRITICAL, "Fence disabled (autodisable)");
gcs_send_text(MAV_SEVERITY_CRITICAL, "Fence disabled (autodisable)");
}
} else if (g.fence_autoenable == 2) {
if (! geofence_set_floor_enabled(false)) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL, "Disable fence floor failed (autodisable)");
gcs_send_text(MAV_SEVERITY_CRITICAL, "Disable fence floor failed (autodisable)");
} else {
gcs_send_text_P(MAV_SEVERITY_CRITICAL, "Fence floor disabled (auto disable)");
gcs_send_text(MAV_SEVERITY_CRITICAL, "Fence floor disabled (auto disable)");
}
}
#endif

View File

@ -1061,7 +1061,7 @@ void Plane::set_servos(void)
void Plane::demo_servos(uint8_t i)
{
while(i > 0) {
gcs_send_text_P(MAV_SEVERITY_WARNING,"Demo Servos!");
gcs_send_text(MAV_SEVERITY_WARNING,"Demo Servos!");
demoing_servos = true;
servo_write(1, 1400);
hal.scheduler->delay(400);

View File

@ -1386,9 +1386,9 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
plane.auto_state.commanded_go_around = true;
result = MAV_RESULT_ACCEPTED;
plane.gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Go around command accepted.");
plane.gcs_send_text(MAV_SEVERITY_CRITICAL,"Go around command accepted.");
} else {
plane.gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Rejected go around command.");
plane.gcs_send_text(MAV_SEVERITY_CRITICAL,"Rejected go around command.");
}
break;
@ -1412,7 +1412,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
if (! plane.geofence_set_floor_enabled(false)) {
result = MAV_RESULT_FAILED;
} else {
plane.gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Fence floor disabled.");
plane.gcs_send_text(MAV_SEVERITY_CRITICAL,"Fence floor disabled.");
}
break;
default:
@ -1932,7 +1932,7 @@ void Plane::mavlink_delay_cb()
}
if (tnow - last_5s > 5000) {
last_5s = tnow;
gcs_send_text_P(MAV_SEVERITY_WARNING, "Initialising APM...");
gcs_send_text(MAV_SEVERITY_WARNING, "Initialising APM...");
}
check_usb_mux();
@ -1992,7 +1992,7 @@ void Plane::gcs_update(void)
}
}
void Plane::gcs_send_text_P(MAV_SEVERITY severity, const prog_char_t *str)
void Plane::gcs_send_text(MAV_SEVERITY severity, const prog_char_t *str)
{
for (uint8_t i=0; i<num_gcs; i++) {
if (gcs[i].initialised) {

View File

@ -149,9 +149,9 @@ int8_t Plane::process_logs(uint8_t argc, const Menu::arg *argv)
void Plane::do_erase_logs(void)
{
gcs_send_text_P(MAV_SEVERITY_WARNING, "Erasing logs");
gcs_send_text(MAV_SEVERITY_WARNING, "Erasing logs");
DataFlash.EraseAll();
gcs_send_text_P(MAV_SEVERITY_WARNING, "Log erase complete");
gcs_send_text(MAV_SEVERITY_WARNING, "Log erase complete");
}
@ -541,12 +541,12 @@ void Plane::log_init(void)
{
DataFlash.Init(log_structure, ARRAY_SIZE(log_structure));
if (!DataFlash.CardInserted()) {
gcs_send_text_P(MAV_SEVERITY_WARNING, "No dataflash card inserted");
gcs_send_text(MAV_SEVERITY_WARNING, "No dataflash card inserted");
g.log_bitmask.set(0);
} else if (DataFlash.NeedPrep()) {
gcs_send_text_P(MAV_SEVERITY_WARNING, "Preparing log system");
gcs_send_text(MAV_SEVERITY_WARNING, "Preparing log system");
DataFlash.Prep();
gcs_send_text_P(MAV_SEVERITY_WARNING, "Prepared log system");
gcs_send_text(MAV_SEVERITY_WARNING, "Prepared log system");
for (uint8_t i=0; i<num_gcs; i++) {
gcs[i].reset_cli_timeout();
}

View File

@ -720,7 +720,7 @@ private:
void gcs_send_mission_item_reached_message(uint16_t mission_index);
void gcs_data_stream_send(void);
void gcs_update(void);
void gcs_send_text_P(MAV_SEVERITY severity, const prog_char_t *str);
void gcs_send_text(MAV_SEVERITY severity, const prog_char_t *str);
void gcs_send_airspeed_calibration(const Vector3f &vg);
void gcs_retry_deferred(void);

View File

@ -52,7 +52,7 @@ void Plane::set_next_WP(const struct Location &loc)
// location as the previous waypoint, to prevent immediately
// considering the waypoint complete
if (location_passed_point(current_loc, prev_WP_loc, next_WP_loc)) {
gcs_send_text_P(MAV_SEVERITY_WARNING, "Resetting prev_WP");
gcs_send_text(MAV_SEVERITY_WARNING, "Resetting prev_WP");
prev_WP_loc = current_loc;
}
@ -100,7 +100,7 @@ void Plane::set_guided_WP(void)
// -------------------------------
void Plane::init_home()
{
gcs_send_text_P(MAV_SEVERITY_WARNING, "init home");
gcs_send_text(MAV_SEVERITY_WARNING, "init home");
ahrs.set_home(gps.location());
home_is_set = HOME_SET_NOT_LOCKED;

View File

@ -291,9 +291,9 @@ bool Plane::verify_command(const AP_Mission::Mission_Command& cmd) // Ret
default:
// error message
if (AP_Mission::is_nav_cmd(cmd)) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"verify_nav: Invalid or no current Nav cmd");
gcs_send_text(MAV_SEVERITY_CRITICAL,"verify_nav: Invalid or no current Nav cmd");
}else{
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"verify_conditon: Invalid or no current Condition cmd");
gcs_send_text(MAV_SEVERITY_CRITICAL,"verify_conditon: Invalid or no current Condition cmd");
}
// return true so that we do not get stuck at this command
return true;
@ -518,9 +518,9 @@ bool Plane::verify_takeoff()
#if GEOFENCE_ENABLED == ENABLED
if (g.fence_autoenable > 0) {
if (! geofence_set_enabled(true, AUTO_TOGGLED)) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL, "Enable fence failed (cannot autoenable");
gcs_send_text(MAV_SEVERITY_CRITICAL, "Enable fence failed (cannot autoenable");
} else {
gcs_send_text_P(MAV_SEVERITY_CRITICAL, "Fence enabled. (autoenabled)");
gcs_send_text(MAV_SEVERITY_CRITICAL, "Fence enabled. (autoenabled)");
}
}
#endif
@ -597,7 +597,7 @@ bool Plane::verify_loiter_time()
loiter.start_time_ms = millis();
}
} else if ((millis() - loiter.start_time_ms) > loiter.time_max_ms) {
gcs_send_text_P(MAV_SEVERITY_WARNING,"verify_nav: LOITER time complete");
gcs_send_text(MAV_SEVERITY_WARNING,"verify_nav: LOITER time complete");
return true;
}
return false;
@ -608,7 +608,7 @@ bool Plane::verify_loiter_turns()
update_loiter();
if (loiter.sum_cd > loiter.total_cd) {
loiter.total_cd = 0;
gcs_send_text_P(MAV_SEVERITY_WARNING,"verify_nav: LOITER orbits complete");
gcs_send_text(MAV_SEVERITY_WARNING,"verify_nav: LOITER orbits complete");
// clear the command queue;
return true;
}
@ -692,7 +692,7 @@ bool Plane::verify_RTL()
update_loiter();
if (auto_state.wp_distance <= (uint32_t)max(g.waypoint_radius,0) ||
nav_controller->reached_loiter_target()) {
gcs_send_text_P(MAV_SEVERITY_WARNING,"Reached home");
gcs_send_text(MAV_SEVERITY_WARNING,"Reached home");
return true;
} else {
return false;
@ -742,7 +742,7 @@ bool Plane::verify_continue_and_change_alt()
bool Plane::verify_altitude_wait(const AP_Mission::Mission_Command &cmd)
{
if (current_loc.alt > cmd.content.altitude_wait.altitude*100.0f) {
gcs_send_text_P(MAV_SEVERITY_WARNING,"Reached altitude");
gcs_send_text(MAV_SEVERITY_WARNING,"Reached altitude");
return true;
}
if (auto_state.sink_rate > cmd.content.altitude_wait.descent_rate) {

View File

@ -77,17 +77,17 @@ void Plane::read_control_switch()
if (hal.util->get_soft_armed() || setup_failsafe_mixing()) {
px4io_override_enabled = true;
// disable output channels to force PX4IO override
gcs_send_text_P(MAV_SEVERITY_WARNING, "PX4IO Override enabled");
gcs_send_text(MAV_SEVERITY_WARNING, "PX4IO Override enabled");
} else {
// we'll try again next loop. The PX4IO code sometimes
// rejects a mixer, probably due to it being busy in
// some way?
gcs_send_text_P(MAV_SEVERITY_WARNING, "PX4IO Override enable failed");
gcs_send_text(MAV_SEVERITY_WARNING, "PX4IO Override enable failed");
}
} else if (!override && px4io_override_enabled) {
px4io_override_enabled = false;
RC_Channel_aux::enable_aux_servos();
gcs_send_text_P(MAV_SEVERITY_WARNING, "PX4IO Override disabled");
gcs_send_text(MAV_SEVERITY_WARNING, "PX4IO Override disabled");
}
if (px4io_override_enabled &&
hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_ARMED) {

View File

@ -7,7 +7,7 @@ void Plane::failsafe_short_on_event(enum failsafe_state fstype)
// This is how to handle a short loss of control signal failsafe.
failsafe.state = fstype;
failsafe.ch3_timer_ms = millis();
gcs_send_text_P(MAV_SEVERITY_WARNING, "Failsafe - Short event on, ");
gcs_send_text(MAV_SEVERITY_WARNING, "Failsafe - Short event on, ");
switch(control_mode)
{
case MANUAL:
@ -52,7 +52,7 @@ void Plane::failsafe_short_on_event(enum failsafe_state fstype)
void Plane::failsafe_long_on_event(enum failsafe_state fstype)
{
// This is how to handle a long loss of control signal failsafe.
gcs_send_text_P(MAV_SEVERITY_WARNING, "Failsafe - Long event on, ");
gcs_send_text(MAV_SEVERITY_WARNING, "Failsafe - Long event on, ");
// If the GCS is locked up we allow control to revert to RC
hal.rcin->clear_overrides();
failsafe.state = fstype;
@ -89,7 +89,7 @@ void Plane::failsafe_long_on_event(enum failsafe_state fstype)
break;
}
if (fstype == FAILSAFE_GCS) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL, "No GCS heartbeat.");
gcs_send_text(MAV_SEVERITY_CRITICAL, "No GCS heartbeat.");
}
gcs_send_text_fmt("flight mode = %u", (unsigned)control_mode);
}
@ -97,7 +97,7 @@ void Plane::failsafe_long_on_event(enum failsafe_state fstype)
void Plane::failsafe_short_off_event()
{
// We're back in radio contact
gcs_send_text_P(MAV_SEVERITY_WARNING, "Failsafe - Short event off");
gcs_send_text(MAV_SEVERITY_WARNING, "Failsafe - Short event off");
failsafe.state = FAILSAFE_NONE;
// re-read the switch so we can return to our preferred mode

View File

@ -137,13 +137,13 @@ void Plane::geofence_load(void)
geofence_state->boundary_uptodate = true;
geofence_state->fence_triggered = false;
gcs_send_text_P(MAV_SEVERITY_WARNING,"geo-fence loaded");
gcs_send_text(MAV_SEVERITY_WARNING,"geo-fence loaded");
gcs_send_message(MSG_FENCE_STATUS);
return;
failed:
g.fence_action.set(FENCE_ACTION_NONE);
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"geo-fence setup error");
gcs_send_text(MAV_SEVERITY_CRITICAL,"geo-fence setup error");
}
/*
@ -335,7 +335,7 @@ void Plane::geofence_check(bool altitude_check_only)
if (geofence_state->fence_triggered && !altitude_check_only) {
// we have moved back inside the fence
geofence_state->fence_triggered = false;
gcs_send_text_P(MAV_SEVERITY_WARNING,"geo-fence OK");
gcs_send_text(MAV_SEVERITY_WARNING,"geo-fence OK");
#if FENCE_TRIGGERED_PIN > 0
hal.gpio->pinMode(FENCE_TRIGGERED_PIN, HAL_GPIO_OUTPUT);
hal.gpio->write(FENCE_TRIGGERED_PIN, 0);
@ -365,7 +365,7 @@ void Plane::geofence_check(bool altitude_check_only)
hal.gpio->write(FENCE_TRIGGERED_PIN, 1);
#endif
gcs_send_text_P(MAV_SEVERITY_WARNING,"geo-fence triggered");
gcs_send_text(MAV_SEVERITY_WARNING,"geo-fence triggered");
gcs_send_message(MSG_FENCE_STATUS);
// see what action the user wants

View File

@ -224,9 +224,9 @@ void Plane::crash_detection_update(void)
if (g.crash_detection_enable == CRASH_DETECT_ACTION_BITMASK_DISABLED) {
if (crashed_near_land_waypoint) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL, "Hard Landing Detected - no action taken");
gcs_send_text(MAV_SEVERITY_CRITICAL, "Hard Landing Detected - no action taken");
} else {
gcs_send_text_P(MAV_SEVERITY_CRITICAL, "Crash Detected - no action taken");
gcs_send_text(MAV_SEVERITY_CRITICAL, "Crash Detected - no action taken");
}
}
else {
@ -235,9 +235,9 @@ void Plane::crash_detection_update(void)
}
auto_state.land_complete = true;
if (crashed_near_land_waypoint) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL, "Hard Landing Detected");
gcs_send_text(MAV_SEVERITY_CRITICAL, "Hard Landing Detected");
} else {
gcs_send_text_P(MAV_SEVERITY_CRITICAL, "Crash Detected");
gcs_send_text(MAV_SEVERITY_CRITICAL, "Crash Detected");
}
}
}

View File

@ -139,7 +139,7 @@ void Plane::disarm_if_autoland_complete()
/* we have auto disarm enabled. See if enough time has passed */
if (millis() - auto_state.last_flying_ms >= g.land_disarm_delay*1000UL) {
if (disarm_motors()) {
gcs_send_text_P(MAV_SEVERITY_WARNING,"Auto-Disarmed");
gcs_send_text(MAV_SEVERITY_WARNING,"Auto-Disarmed");
}
}
}
@ -301,12 +301,12 @@ bool Plane::jump_to_landing_sequence(void)
mission.resume();
}
gcs_send_text_P(MAV_SEVERITY_WARNING, "Landing sequence begun.");
gcs_send_text(MAV_SEVERITY_WARNING, "Landing sequence begun.");
return true;
}
}
gcs_send_text_P(MAV_SEVERITY_CRITICAL, "Unable to start landing sequence.");
gcs_send_text(MAV_SEVERITY_CRITICAL, "Unable to start landing sequence.");
return false;
}

View File

@ -21,7 +21,7 @@ void Plane::parachute_release()
}
// send message to gcs and dataflash
gcs_send_text_P(MAV_SEVERITY_CRITICAL,"Parachute: Released");
gcs_send_text(MAV_SEVERITY_CRITICAL,"Parachute: Released");
// release parachute
parachute.release();
@ -42,7 +42,7 @@ bool Plane::parachute_manual_release()
// do not release if vehicle is not flying
if (!is_flying()) {
// warn user of reason for failure
gcs_send_text_P(MAV_SEVERITY_WARNING,"Parachute: not flying");
gcs_send_text(MAV_SEVERITY_WARNING,"Parachute: not flying");
return false;
}

View File

@ -5,10 +5,10 @@
void Plane::init_barometer(void)
{
gcs_send_text_P(MAV_SEVERITY_WARNING, "Calibrating barometer");
gcs_send_text(MAV_SEVERITY_WARNING, "Calibrating barometer");
barometer.calibrate();
gcs_send_text_P(MAV_SEVERITY_WARNING, "barometer calibration complete");
gcs_send_text(MAV_SEVERITY_WARNING, "barometer calibration complete");
}
void Plane::init_rangefinder(void)
@ -75,7 +75,7 @@ void Plane::zero_airspeed(bool in_startup)
read_airspeed();
// update barometric calibration with new airspeed supplied temperature
barometer.update_calibration();
gcs_send_text_P(MAV_SEVERITY_WARNING,"zero airspeed calibrated");
gcs_send_text(MAV_SEVERITY_WARNING,"zero airspeed calibrated");
}
// read_battery - reads battery voltage and current and invokes failsafe

View File

@ -266,10 +266,10 @@ void Plane::startup_ground(void)
{
set_mode(INITIALISING);
gcs_send_text_P(MAV_SEVERITY_WARNING,"<startup_ground> GROUND START");
gcs_send_text(MAV_SEVERITY_WARNING,"<startup_ground> GROUND START");
#if (GROUND_START_DELAY > 0)
gcs_send_text_P(MAV_SEVERITY_WARNING,"<startup_ground> With Delay");
gcs_send_text(MAV_SEVERITY_WARNING,"<startup_ground> With Delay");
delay(GROUND_START_DELAY * 1000);
#endif
@ -316,7 +316,7 @@ void Plane::startup_ground(void)
ins.set_raw_logging(should_log(MASK_LOG_IMU_RAW));
ins.set_dataflash(&DataFlash);
gcs_send_text_P(MAV_SEVERITY_WARNING,"\n\n Ready to FLY.");
gcs_send_text(MAV_SEVERITY_WARNING,"\n\n Ready to FLY.");
}
enum FlightMode Plane::get_previous_mode() {
@ -560,14 +560,14 @@ void Plane::startup_INS_ground(void)
while (barometer.get_last_update() == 0) {
// the barometer begins updating when we get the first
// HIL_STATE message
gcs_send_text_P(MAV_SEVERITY_WARNING, "Waiting for first HIL_STATE message");
gcs_send_text(MAV_SEVERITY_WARNING, "Waiting for first HIL_STATE message");
hal.scheduler->delay(1000);
}
}
#endif
if (ins.gyro_calibration_timing() != AP_InertialSensor::GYRO_CAL_NEVER) {
gcs_send_text_P(MAV_SEVERITY_ALERT, "Beginning INS calibration; do not move plane");
gcs_send_text(MAV_SEVERITY_ALERT, "Beginning INS calibration; do not move plane");
hal.scheduler->delay(100);
}
@ -588,7 +588,7 @@ void Plane::startup_INS_ground(void)
// --------------------------
zero_airspeed(true);
} else {
gcs_send_text_P(MAV_SEVERITY_WARNING,"NO airspeed");
gcs_send_text(MAV_SEVERITY_WARNING,"NO airspeed");
}
}

View File

@ -179,7 +179,7 @@ int8_t Plane::takeoff_tail_hold(void)
return_zero:
if (auto_state.fbwa_tdrag_takeoff_mode) {
gcs_send_text_P(MAV_SEVERITY_WARNING, "FBWA tdrag off");
gcs_send_text(MAV_SEVERITY_WARNING, "FBWA tdrag off");
auto_state.fbwa_tdrag_takeoff_mode = false;
}
return 0;