Plane: Text revisions

text revisions
This commit is contained in:
Luis Vale Gonçalves 2015-11-18 19:17:50 +00:00 committed by Andrew Tridgell
parent 999e99c6f3
commit b7f3782e4e
16 changed files with 74 additions and 74 deletions

View File

@ -625,7 +625,7 @@ void Plane::update_flight_mode(void)
if (tdrag_mode && !auto_state.fbwa_tdrag_takeoff_mode) { if (tdrag_mode && !auto_state.fbwa_tdrag_takeoff_mode) {
if (auto_state.highest_airspeed < g.takeoff_tdrag_speed1) { if (auto_state.highest_airspeed < g.takeoff_tdrag_speed1) {
auto_state.fbwa_tdrag_takeoff_mode = true; auto_state.fbwa_tdrag_takeoff_mode = true;
gcs_send_text(MAV_SEVERITY_WARNING, "FBWA tdrag mode\n"); gcs_send_text(MAV_SEVERITY_WARNING, "FBWA tdrag mode");
} }
} }
} }
@ -786,7 +786,7 @@ void Plane::set_flight_stage(AP_SpdHgtControl::FlightStage fs)
break; break;
case AP_SpdHgtControl::FLIGHT_LAND_ABORT: case AP_SpdHgtControl::FLIGHT_LAND_ABORT:
gcs_send_text_fmt(MAV_SEVERITY_NOTICE, "Landing aborted via throttle, climbing to %dm", auto_state.takeoff_altitude_rel_cm/100); gcs_send_text_fmt(MAV_SEVERITY_NOTICE, "Landing aborted via throttle. Climbing to %dm", auto_state.takeoff_altitude_rel_cm/100);
break; break;
case AP_SpdHgtControl::FLIGHT_LAND_FINAL: case AP_SpdHgtControl::FLIGHT_LAND_FINAL:

View File

@ -609,7 +609,7 @@ bool Plane::suppress_throttle(void)
if (relative_altitude_abs_cm() >= 1000) { if (relative_altitude_abs_cm() >= 1000) {
// we're more than 10m from the home altitude // we're more than 10m from the home altitude
throttle_suppressed = false; throttle_suppressed = false;
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Throttle enabled - altitude %.2f", gcs_send_text_fmt(MAV_SEVERITY_INFO, "Throttle enabled. Altitude %.2f",
(double)(relative_altitude_abs_cm()*0.01f)); (double)(relative_altitude_abs_cm()*0.01f));
return false; return false;
} }
@ -620,7 +620,7 @@ bool Plane::suppress_throttle(void)
// groundspeed with bad GPS reception // groundspeed with bad GPS reception
if ((!ahrs.airspeed_sensor_enabled()) || airspeed.get_airspeed() >= 5) { if ((!ahrs.airspeed_sensor_enabled()) || airspeed.get_airspeed() >= 5) {
// we're moving at more than 5 m/s // we're moving at more than 5 m/s
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Throttle enabled - speed %.2f airspeed %.2f", gcs_send_text_fmt(MAV_SEVERITY_INFO, "Throttle enabled. Speed %.2f airspeed %.2f",
(double)gps.ground_speed(), (double)gps.ground_speed(),
(double)airspeed.get_airspeed()); (double)airspeed.get_airspeed());
throttle_suppressed = false; throttle_suppressed = false;
@ -1061,7 +1061,7 @@ void Plane::set_servos(void)
void Plane::demo_servos(uint8_t i) void Plane::demo_servos(uint8_t i)
{ {
while(i > 0) { while(i > 0) {
gcs_send_text(MAV_SEVERITY_INFO,"Demo Servos!"); gcs_send_text(MAV_SEVERITY_INFO,"Demo servos");
demoing_servos = true; demoing_servos = true;
servo_write(1, 1400); servo_write(1, 1400);
hal.scheduler->delay(400); hal.scheduler->delay(400);

View File

@ -1135,7 +1135,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
uint8_t result = MAV_RESULT_UNSUPPORTED; uint8_t result = MAV_RESULT_UNSUPPORTED;
// do command // do command
send_text(MAV_SEVERITY_INFO,"command received: "); send_text(MAV_SEVERITY_INFO,"Command received: ");
switch(packet.command) { switch(packet.command) {
@ -1386,9 +1386,9 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
plane.auto_state.commanded_go_around = true; plane.auto_state.commanded_go_around = true;
result = MAV_RESULT_ACCEPTED; result = MAV_RESULT_ACCEPTED;
plane.gcs_send_text(MAV_SEVERITY_INFO,"Go around command accepted."); plane.gcs_send_text(MAV_SEVERITY_INFO,"Go around command accepted");
} else { } else {
plane.gcs_send_text(MAV_SEVERITY_NOTICE,"Rejected go around command."); plane.gcs_send_text(MAV_SEVERITY_NOTICE,"Rejected go around command");
} }
break; break;
@ -1412,7 +1412,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
if (! plane.geofence_set_floor_enabled(false)) { if (! plane.geofence_set_floor_enabled(false)) {
result = MAV_RESULT_FAILED; result = MAV_RESULT_FAILED;
} else { } else {
plane.gcs_send_text(MAV_SEVERITY_NOTICE,"Fence floor disabled."); plane.gcs_send_text(MAV_SEVERITY_NOTICE,"Fence floor disabled");
} }
break; break;
default: default:
@ -1454,7 +1454,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
plane.Log_Write_Home_And_Origin(); plane.Log_Write_Home_And_Origin();
GCS_MAVLINK::send_home_all(new_home_loc); GCS_MAVLINK::send_home_all(new_home_loc);
result = MAV_RESULT_ACCEPTED; result = MAV_RESULT_ACCEPTED;
plane.gcs_send_text_fmt(MAV_SEVERITY_INFO, "set home to %.6f %.6f at %um", plane.gcs_send_text_fmt(MAV_SEVERITY_INFO, "Set HOME to %.6f %.6f at %um",
(double)(new_home_loc.lat*1.0e-7f), (double)(new_home_loc.lat*1.0e-7f),
(double)(new_home_loc.lng*1.0e-7f), (double)(new_home_loc.lng*1.0e-7f),
(uint32_t)(new_home_loc.alt*0.01f)); (uint32_t)(new_home_loc.alt*0.01f));
@ -1612,11 +1612,11 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
mavlink_fence_point_t packet; mavlink_fence_point_t packet;
mavlink_msg_fence_point_decode(msg, &packet); mavlink_msg_fence_point_decode(msg, &packet);
if (plane.g.fence_action != FENCE_ACTION_NONE) { if (plane.g.fence_action != FENCE_ACTION_NONE) {
send_text(MAV_SEVERITY_WARNING,"fencing must be disabled"); send_text(MAV_SEVERITY_WARNING,"Fencing must be disabled");
} else if (packet.count != plane.g.fence_total) { } else if (packet.count != plane.g.fence_total) {
send_text(MAV_SEVERITY_WARNING,"bad fence point"); send_text(MAV_SEVERITY_WARNING,"Bad fence point");
} else if (fabsf(packet.lat) > 90.0f || fabsf(packet.lng) > 180.0f) { } else if (fabsf(packet.lat) > 90.0f || fabsf(packet.lng) > 180.0f) {
send_text(MAV_SEVERITY_WARNING,"invalid fence point, lat or lng too large"); send_text(MAV_SEVERITY_WARNING,"Invalid fence point, lat or lng too large");
} else { } else {
Vector2l point; Vector2l point;
point.x = packet.lat*1.0e7f; point.x = packet.lat*1.0e7f;
@ -1631,7 +1631,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
mavlink_fence_fetch_point_t packet; mavlink_fence_fetch_point_t packet;
mavlink_msg_fence_fetch_point_decode(msg, &packet); mavlink_msg_fence_fetch_point_decode(msg, &packet);
if (packet.idx >= plane.g.fence_total) { if (packet.idx >= plane.g.fence_total) {
send_text(MAV_SEVERITY_WARNING,"bad fence point"); send_text(MAV_SEVERITY_WARNING,"Bad fence point");
} else { } else {
Vector2l point = plane.get_fence_point_with_index(packet.idx); Vector2l point = plane.get_fence_point_with_index(packet.idx);
mavlink_msg_fence_point_send_buf(msg, chan, msg->sysid, msg->compid, packet.idx, plane.g.fence_total, mavlink_msg_fence_point_send_buf(msg, chan, msg->sysid, msg->compid, packet.idx, plane.g.fence_total,
@ -1648,12 +1648,12 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
if (packet.idx >= plane.rally.get_rally_total() || if (packet.idx >= plane.rally.get_rally_total() ||
packet.idx >= plane.rally.get_rally_max()) { packet.idx >= plane.rally.get_rally_max()) {
send_text(MAV_SEVERITY_WARNING,"bad rally point message ID"); send_text(MAV_SEVERITY_WARNING,"Bad rally point message ID");
break; break;
} }
if (packet.count != plane.rally.get_rally_total()) { if (packet.count != plane.rally.get_rally_total()) {
send_text(MAV_SEVERITY_WARNING,"bad rally point message count"); send_text(MAV_SEVERITY_WARNING,"Bad rally point message count");
break; break;
} }
@ -1673,12 +1673,12 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
mavlink_rally_fetch_point_t packet; mavlink_rally_fetch_point_t packet;
mavlink_msg_rally_fetch_point_decode(msg, &packet); mavlink_msg_rally_fetch_point_decode(msg, &packet);
if (packet.idx > plane.rally.get_rally_total()) { if (packet.idx > plane.rally.get_rally_total()) {
send_text(MAV_SEVERITY_WARNING, "bad rally point index"); send_text(MAV_SEVERITY_WARNING, "Bad rally point index");
break; break;
} }
RallyLocation rally_point; RallyLocation rally_point;
if (!plane.rally.get_rally_point_with_index(packet.idx, rally_point)) { if (!plane.rally.get_rally_point_with_index(packet.idx, rally_point)) {
send_text(MAV_SEVERITY_WARNING, "failed to set rally point"); send_text(MAV_SEVERITY_WARNING, "Failed to set rally point");
break; break;
} }
@ -1893,7 +1893,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
plane.home_is_set = HOME_SET_NOT_LOCKED; plane.home_is_set = HOME_SET_NOT_LOCKED;
plane.Log_Write_Home_And_Origin(); plane.Log_Write_Home_And_Origin();
GCS_MAVLINK::send_home_all(new_home_loc); GCS_MAVLINK::send_home_all(new_home_loc);
plane.gcs_send_text_fmt(MAV_SEVERITY_INFO, "set home to %.6f %.6f at %um", plane.gcs_send_text_fmt(MAV_SEVERITY_INFO, "Set HOME to %.6f %.6f at %um",
(double)(new_home_loc.lat*1.0e-7f), (double)(new_home_loc.lat*1.0e-7f),
(double)(new_home_loc.lng*1.0e-7f), (double)(new_home_loc.lng*1.0e-7f),
(uint32_t)(new_home_loc.alt*0.01f)); (uint32_t)(new_home_loc.alt*0.01f));

View File

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

View File

@ -56,7 +56,7 @@ bool AP_Arming_Plane::pre_arm_checks(bool report)
plane.g.throttle_fs_value < plane.g.throttle_fs_value <
plane.channel_throttle->radio_max) { plane.channel_throttle->radio_max) {
if (report) { if (report) {
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: invalid THR_FS_VALUE for rev throttle"); GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: Invalid THR_FS_VALUE for rev throttle");
} }
ret = false; ret = false;
} }

View File

@ -52,7 +52,7 @@ void Plane::set_next_WP(const struct Location &loc)
// location as the previous waypoint, to prevent immediately // location as the previous waypoint, to prevent immediately
// considering the waypoint complete // considering the waypoint complete
if (location_passed_point(current_loc, prev_WP_loc, next_WP_loc)) { if (location_passed_point(current_loc, prev_WP_loc, next_WP_loc)) {
gcs_send_text(MAV_SEVERITY_NOTICE, "Resetting prev_WP"); gcs_send_text(MAV_SEVERITY_NOTICE, "Resetting previous waypoint");
prev_WP_loc = current_loc; prev_WP_loc = current_loc;
} }
@ -100,14 +100,14 @@ void Plane::set_guided_WP(void)
// ------------------------------- // -------------------------------
void Plane::init_home() void Plane::init_home()
{ {
gcs_send_text(MAV_SEVERITY_INFO, "init home"); gcs_send_text(MAV_SEVERITY_INFO, "Init HOME");
ahrs.set_home(gps.location()); ahrs.set_home(gps.location());
home_is_set = HOME_SET_NOT_LOCKED; home_is_set = HOME_SET_NOT_LOCKED;
Log_Write_Home_And_Origin(); Log_Write_Home_And_Origin();
GCS_MAVLINK::send_home_all(gps.location()); GCS_MAVLINK::send_home_all(gps.location());
gcs_send_text_fmt(MAV_SEVERITY_INFO, "gps alt: %lu", (unsigned long)home.alt); gcs_send_text_fmt(MAV_SEVERITY_INFO, "GPS alt: %lu", (unsigned long)home.alt);
// Save Home to EEPROM // Save Home to EEPROM
mission.write_home_to_storage(); mission.write_home_to_storage();

View File

@ -140,15 +140,15 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd)
#if GEOFENCE_ENABLED == ENABLED #if GEOFENCE_ENABLED == ENABLED
if (cmd.p1 != 2) { if (cmd.p1 != 2) {
if (!geofence_set_enabled((bool) cmd.p1, AUTO_TOGGLED)) { if (!geofence_set_enabled((bool) cmd.p1, AUTO_TOGGLED)) {
gcs_send_text_fmt(MAV_SEVERITY_WARNING, "Unable to set fence enabled state to %u", cmd.p1); gcs_send_text_fmt(MAV_SEVERITY_WARNING, "Unable to set fence. Enabled state to %u", cmd.p1);
} else { } else {
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Set fence enabled state to %u", cmd.p1); gcs_send_text_fmt(MAV_SEVERITY_INFO, "Set fence enabled state to %u", cmd.p1);
} }
} else { //commanding to only disable floor } else { //commanding to only disable floor
if (! geofence_set_floor_enabled(false)) { if (! geofence_set_floor_enabled(false)) {
gcs_send_text_fmt(MAV_SEVERITY_WARNING, "Unabled to disable fence floor.\n"); gcs_send_text_fmt(MAV_SEVERITY_WARNING, "Unabled to disable fence floor");
} else { } else {
gcs_send_text_fmt(MAV_SEVERITY_WARNING, "Fence floor disabled.\n"); gcs_send_text_fmt(MAV_SEVERITY_WARNING, "Fence floor disabled");
} }
} }
#endif #endif
@ -294,9 +294,9 @@ bool Plane::verify_command(const AP_Mission::Mission_Command& cmd) // Ret
default: default:
// error message // error message
if (AP_Mission::is_nav_cmd(cmd)) { if (AP_Mission::is_nav_cmd(cmd)) {
gcs_send_text(MAV_SEVERITY_WARNING,"verify_nav: Invalid or no current Nav cmd"); gcs_send_text(MAV_SEVERITY_WARNING,"Verify nav. Invalid or no current nav cmd");
}else{ }else{
gcs_send_text(MAV_SEVERITY_WARNING,"verify_conditon: Invalid or no current Condition cmd"); gcs_send_text(MAV_SEVERITY_WARNING,"Verify conditon. Invalid or no current condition cmd");
} }
// return true so that we do not get stuck at this command // return true so that we do not get stuck at this command
return true; return true;
@ -522,7 +522,7 @@ bool Plane::verify_takeoff()
if (! geofence_set_enabled(true, AUTO_TOGGLED)) { if (! geofence_set_enabled(true, AUTO_TOGGLED)) {
gcs_send_text(MAV_SEVERITY_NOTICE, "Enable fence failed (cannot autoenable"); gcs_send_text(MAV_SEVERITY_NOTICE, "Enable fence failed (cannot autoenable");
} else { } else {
gcs_send_text(MAV_SEVERITY_INFO, "Fence enabled. (autoenabled)"); gcs_send_text(MAV_SEVERITY_INFO, "Fence enabled (autoenabled)");
} }
} }
#endif #endif
@ -567,7 +567,7 @@ bool Plane::verify_nav_wp(const AP_Mission::Mission_Command& cmd)
} }
if (auto_state.wp_distance <= acceptance_distance) { if (auto_state.wp_distance <= acceptance_distance) {
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Reached Waypoint #%i dist %um", gcs_send_text_fmt(MAV_SEVERITY_INFO, "Reached waypoint #%i dist %um",
(unsigned)mission.get_current_nav_cmd().index, (unsigned)mission.get_current_nav_cmd().index,
(unsigned)get_distance(current_loc, next_WP_loc)); (unsigned)get_distance(current_loc, next_WP_loc));
return true; return true;
@ -575,7 +575,7 @@ bool Plane::verify_nav_wp(const AP_Mission::Mission_Command& cmd)
// have we flown past the waypoint? // have we flown past the waypoint?
if (location_passed_point(current_loc, prev_WP_loc, next_WP_loc)) { if (location_passed_point(current_loc, prev_WP_loc, next_WP_loc)) {
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Passed Waypoint #%i dist %um", gcs_send_text_fmt(MAV_SEVERITY_INFO, "Passed waypoint #%i dist %um",
(unsigned)mission.get_current_nav_cmd().index, (unsigned)mission.get_current_nav_cmd().index,
(unsigned)get_distance(current_loc, next_WP_loc)); (unsigned)get_distance(current_loc, next_WP_loc));
return true; return true;
@ -599,7 +599,7 @@ bool Plane::verify_loiter_time()
loiter.start_time_ms = millis(); loiter.start_time_ms = millis();
} }
} else if ((millis() - loiter.start_time_ms) > loiter.time_max_ms) { } else if ((millis() - loiter.start_time_ms) > loiter.time_max_ms) {
gcs_send_text(MAV_SEVERITY_WARNING,"verify_nav: LOITER time complete"); gcs_send_text(MAV_SEVERITY_WARNING,"Verify nav: LOITER time complete");
return true; return true;
} }
return false; return false;
@ -610,7 +610,7 @@ bool Plane::verify_loiter_turns()
update_loiter(); update_loiter();
if (loiter.sum_cd > loiter.total_cd) { if (loiter.sum_cd > loiter.total_cd) {
loiter.total_cd = 0; loiter.total_cd = 0;
gcs_send_text(MAV_SEVERITY_WARNING,"verify_nav: LOITER orbits complete"); gcs_send_text(MAV_SEVERITY_WARNING,"Verify nav: LOITER orbits complete");
// clear the command queue; // clear the command queue;
return true; return true;
} }
@ -694,7 +694,7 @@ bool Plane::verify_RTL()
update_loiter(); update_loiter();
if (auto_state.wp_distance <= (uint32_t)max(g.waypoint_radius,0) || if (auto_state.wp_distance <= (uint32_t)max(g.waypoint_radius,0) ||
nav_controller->reached_loiter_target()) { nav_controller->reached_loiter_target()) {
gcs_send_text(MAV_SEVERITY_INFO,"Reached home"); gcs_send_text(MAV_SEVERITY_INFO,"Reached HOME");
return true; return true;
} else { } else {
return false; return false;
@ -982,7 +982,7 @@ bool Plane::verify_command_callback(const AP_Mission::Mission_Command& cmd)
void Plane::exit_mission_callback() void Plane::exit_mission_callback()
{ {
if (control_mode == AUTO) { if (control_mode == AUTO) {
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Returning to Home"); gcs_send_text_fmt(MAV_SEVERITY_INFO, "Returning to HOME");
memset(&auto_rtl_command, 0, sizeof(auto_rtl_command)); memset(&auto_rtl_command, 0, sizeof(auto_rtl_command));
auto_rtl_command.content.location = auto_rtl_command.content.location =
rally.calc_best_rally_or_home_location(current_loc, get_RTL_altitude()); rally.calc_best_rally_or_home_location(current_loc, get_RTL_altitude());

View File

@ -77,17 +77,17 @@ void Plane::read_control_switch()
if (hal.util->get_soft_armed() || setup_failsafe_mixing()) { if (hal.util->get_soft_armed() || setup_failsafe_mixing()) {
px4io_override_enabled = true; px4io_override_enabled = true;
// disable output channels to force PX4IO override // disable output channels to force PX4IO override
gcs_send_text(MAV_SEVERITY_WARNING, "PX4IO Override enabled"); gcs_send_text(MAV_SEVERITY_WARNING, "PX4IO override enabled");
} else { } else {
// we'll try again next loop. The PX4IO code sometimes // we'll try again next loop. The PX4IO code sometimes
// rejects a mixer, probably due to it being busy in // rejects a mixer, probably due to it being busy in
// some way? // some way?
gcs_send_text(MAV_SEVERITY_WARNING, "PX4IO Override enable failed"); gcs_send_text(MAV_SEVERITY_WARNING, "PX4IO override enable failed");
} }
} else if (!override && px4io_override_enabled) { } else if (!override && px4io_override_enabled) {
px4io_override_enabled = false; px4io_override_enabled = false;
RC_Channel_aux::enable_aux_servos(); RC_Channel_aux::enable_aux_servos();
gcs_send_text(MAV_SEVERITY_WARNING, "PX4IO Override disabled"); gcs_send_text(MAV_SEVERITY_WARNING, "PX4IO override disabled");
} }
if (px4io_override_enabled && if (px4io_override_enabled &&
hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_ARMED) { 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. // This is how to handle a short loss of control signal failsafe.
failsafe.state = fstype; failsafe.state = fstype;
failsafe.ch3_timer_ms = millis(); failsafe.ch3_timer_ms = millis();
gcs_send_text(MAV_SEVERITY_WARNING, "Failsafe - Short event on, "); gcs_send_text(MAV_SEVERITY_WARNING, "Failsafe. Short event on, ");
switch(control_mode) switch(control_mode)
{ {
case MANUAL: case MANUAL:
@ -46,13 +46,13 @@ void Plane::failsafe_short_on_event(enum failsafe_state fstype)
default: default:
break; break;
} }
gcs_send_text_fmt(MAV_SEVERITY_INFO, "flight mode = %u", (unsigned)control_mode); gcs_send_text_fmt(MAV_SEVERITY_INFO, "Flight mode = %u", (unsigned)control_mode);
} }
void Plane::failsafe_long_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. // This is how to handle a long loss of control signal failsafe.
gcs_send_text(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 // If the GCS is locked up we allow control to revert to RC
hal.rcin->clear_overrides(); hal.rcin->clear_overrides();
failsafe.state = fstype; failsafe.state = fstype;
@ -89,15 +89,15 @@ void Plane::failsafe_long_on_event(enum failsafe_state fstype)
break; break;
} }
if (fstype == FAILSAFE_GCS) { if (fstype == FAILSAFE_GCS) {
gcs_send_text(MAV_SEVERITY_CRITICAL, "No GCS heartbeat."); gcs_send_text(MAV_SEVERITY_CRITICAL, "No GCS heartbeat");
} }
gcs_send_text_fmt(MAV_SEVERITY_INFO, "flight mode = %u", (unsigned)control_mode); gcs_send_text_fmt(MAV_SEVERITY_INFO, "Flight mode = %u", (unsigned)control_mode);
} }
void Plane::failsafe_short_off_event() void Plane::failsafe_short_off_event()
{ {
// We're back in radio contact // We're back in radio contact
gcs_send_text(MAV_SEVERITY_WARNING, "Failsafe - Short event off"); gcs_send_text(MAV_SEVERITY_WARNING, "Failsafe. Short event off");
failsafe.state = FAILSAFE_NONE; failsafe.state = FAILSAFE_NONE;
// re-read the switch so we can return to our preferred mode // re-read the switch so we can return to our preferred mode
@ -113,7 +113,7 @@ void Plane::low_battery_event(void)
if (failsafe.low_battery) { if (failsafe.low_battery) {
return; return;
} }
gcs_send_text_fmt(MAV_SEVERITY_WARNING, "Low Battery %.2fV Used %.0f mAh", gcs_send_text_fmt(MAV_SEVERITY_WARNING, "Low battery %.2fV used %.0f mAh",
(double)battery.voltage(), (double)battery.current_total_mah()); (double)battery.voltage(), (double)battery.current_total_mah());
if (flight_stage != AP_SpdHgtControl::FLIGHT_LAND_FINAL && if (flight_stage != AP_SpdHgtControl::FLIGHT_LAND_FINAL &&
flight_stage != AP_SpdHgtControl::FLIGHT_LAND_APPROACH) { flight_stage != AP_SpdHgtControl::FLIGHT_LAND_APPROACH) {

View File

@ -137,13 +137,13 @@ void Plane::geofence_load(void)
geofence_state->boundary_uptodate = true; geofence_state->boundary_uptodate = true;
geofence_state->fence_triggered = false; geofence_state->fence_triggered = false;
gcs_send_text(MAV_SEVERITY_INFO,"geo-fence loaded"); gcs_send_text(MAV_SEVERITY_INFO,"Geofence loaded");
gcs_send_message(MSG_FENCE_STATUS); gcs_send_message(MSG_FENCE_STATUS);
return; return;
failed: failed:
g.fence_action.set(FENCE_ACTION_NONE); g.fence_action.set(FENCE_ACTION_NONE);
gcs_send_text(MAV_SEVERITY_WARNING,"geo-fence setup error"); gcs_send_text(MAV_SEVERITY_WARNING,"Geofence setup error");
} }
/* /*
@ -335,7 +335,7 @@ void Plane::geofence_check(bool altitude_check_only)
if (geofence_state->fence_triggered && !altitude_check_only) { if (geofence_state->fence_triggered && !altitude_check_only) {
// we have moved back inside the fence // we have moved back inside the fence
geofence_state->fence_triggered = false; geofence_state->fence_triggered = false;
gcs_send_text(MAV_SEVERITY_INFO,"geo-fence OK"); gcs_send_text(MAV_SEVERITY_INFO,"Geofence OK");
#if FENCE_TRIGGERED_PIN > 0 #if FENCE_TRIGGERED_PIN > 0
hal.gpio->pinMode(FENCE_TRIGGERED_PIN, HAL_GPIO_OUTPUT); hal.gpio->pinMode(FENCE_TRIGGERED_PIN, HAL_GPIO_OUTPUT);
hal.gpio->write(FENCE_TRIGGERED_PIN, 0); 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); hal.gpio->write(FENCE_TRIGGERED_PIN, 1);
#endif #endif
gcs_send_text(MAV_SEVERITY_NOTICE,"geo-fence triggered"); gcs_send_text(MAV_SEVERITY_NOTICE,"Geofence triggered");
gcs_send_message(MSG_FENCE_STATUS); gcs_send_message(MSG_FENCE_STATUS);
// see what action the user wants // 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 (g.crash_detection_enable == CRASH_DETECT_ACTION_BITMASK_DISABLED) {
if (crashed_near_land_waypoint) { if (crashed_near_land_waypoint) {
gcs_send_text(MAV_SEVERITY_CRITICAL, "Hard Landing Detected - no action taken"); gcs_send_text(MAV_SEVERITY_CRITICAL, "Hard landing detected. No action taken");
} else { } else {
gcs_send_text(MAV_SEVERITY_EMERGENCY, "Crash Detected - no action taken"); gcs_send_text(MAV_SEVERITY_EMERGENCY, "Crash detected. No action taken");
} }
} }
else { else {
@ -235,9 +235,9 @@ void Plane::crash_detection_update(void)
} }
auto_state.land_complete = true; auto_state.land_complete = true;
if (crashed_near_land_waypoint) { if (crashed_near_land_waypoint) {
gcs_send_text(MAV_SEVERITY_CRITICAL, "Hard Landing Detected"); gcs_send_text(MAV_SEVERITY_CRITICAL, "Hard landing detected");
} else { } else {
gcs_send_text(MAV_SEVERITY_EMERGENCY, "Crash Detected"); gcs_send_text(MAV_SEVERITY_EMERGENCY, "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 */ /* we have auto disarm enabled. See if enough time has passed */
if (millis() - auto_state.last_flying_ms >= g.land_disarm_delay*1000UL) { if (millis() - auto_state.last_flying_ms >= g.land_disarm_delay*1000UL) {
if (disarm_motors()) { if (disarm_motors()) {
gcs_send_text(MAV_SEVERITY_INFO,"Auto-Disarmed"); gcs_send_text(MAV_SEVERITY_INFO,"Auto disarmed");
} }
} }
} }
@ -260,7 +260,7 @@ bool Plane::restart_landing_sequence()
mission.set_current_cmd(current_index+1)) mission.set_current_cmd(current_index+1))
{ {
// if the next immediate command is MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT to climb, do it // if the next immediate command is MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT to climb, do it
gcs_send_text_fmt(MAV_SEVERITY_NOTICE, "Restarted landing sequence climbing to %dm", cmd.content.location.alt/100); gcs_send_text_fmt(MAV_SEVERITY_NOTICE, "Restarted landing sequence. Climbing to %dm", cmd.content.location.alt/100);
success = true; success = true;
} }
else if (do_land_start_index != 0 && else if (do_land_start_index != 0 &&
@ -278,7 +278,7 @@ bool Plane::restart_landing_sequence()
gcs_send_text_fmt(MAV_SEVERITY_NOTICE, "Restarted landing sequence at waypoint %d", prev_cmd_with_wp_index); gcs_send_text_fmt(MAV_SEVERITY_NOTICE, "Restarted landing sequence at waypoint %d", prev_cmd_with_wp_index);
success = true; success = true;
} else { } else {
gcs_send_text_fmt(MAV_SEVERITY_WARNING, "Unable to restart landing sequence!"); gcs_send_text_fmt(MAV_SEVERITY_WARNING, "Unable to restart landing sequence");
success = false; success = false;
} }
return success; return success;
@ -301,12 +301,12 @@ bool Plane::jump_to_landing_sequence(void)
mission.resume(); mission.resume();
} }
gcs_send_text(MAV_SEVERITY_INFO, "Landing sequence begun."); gcs_send_text(MAV_SEVERITY_INFO, "Landing sequence start");
return true; 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; return false;
} }

View File

@ -42,12 +42,12 @@ bool Plane::parachute_manual_release()
// do not release if vehicle is not flying // do not release if vehicle is not flying
if (!is_flying()) { if (!is_flying()) {
// warn user of reason for failure // warn user of reason for failure
gcs_send_text(MAV_SEVERITY_WARNING,"Parachute: not flying"); gcs_send_text(MAV_SEVERITY_WARNING,"Parachute: Not flying");
return false; return false;
} }
if (relative_altitude() < parachute.alt_min()) { if (relative_altitude() < parachute.alt_min()) {
gcs_send_text_fmt(MAV_SEVERITY_WARNING, "Parachute: too low"); gcs_send_text_fmt(MAV_SEVERITY_WARNING, "Parachute: Too low");
return false; return false;
} }

View File

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

View File

@ -254,10 +254,10 @@ void Plane::startup_ground(void)
{ {
set_mode(INITIALISING); set_mode(INITIALISING);
gcs_send_text(MAV_SEVERITY_INFO,"<startup_ground> GROUND START"); gcs_send_text(MAV_SEVERITY_INFO,"<startup_ground> Ground start");
#if (GROUND_START_DELAY > 0) #if (GROUND_START_DELAY > 0)
gcs_send_text(MAV_SEVERITY_NOTICE,"<startup_ground> With Delay"); gcs_send_text(MAV_SEVERITY_NOTICE,"<startup_ground> With delay");
delay(GROUND_START_DELAY * 1000); delay(GROUND_START_DELAY * 1000);
#endif #endif
@ -304,7 +304,7 @@ void Plane::startup_ground(void)
ins.set_raw_logging(should_log(MASK_LOG_IMU_RAW)); ins.set_raw_logging(should_log(MASK_LOG_IMU_RAW));
ins.set_dataflash(&DataFlash); ins.set_dataflash(&DataFlash);
gcs_send_text(MAV_SEVERITY_INFO,"\n\n Ready to FLY."); gcs_send_text(MAV_SEVERITY_INFO,"Ready to fly");
} }
enum FlightMode Plane::get_previous_mode() { enum FlightMode Plane::get_previous_mode() {
@ -558,7 +558,7 @@ void Plane::startup_INS_ground(void)
#endif #endif
if (ins.gyro_calibration_timing() != AP_InertialSensor::GYRO_CAL_NEVER) { if (ins.gyro_calibration_timing() != AP_InertialSensor::GYRO_CAL_NEVER) {
gcs_send_text(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); hal.scheduler->delay(100);
} }
@ -579,7 +579,7 @@ void Plane::startup_INS_ground(void)
// -------------------------- // --------------------------
zero_airspeed(true); zero_airspeed(true);
} else { } else {
gcs_send_text(MAV_SEVERITY_WARNING,"NO airspeed"); gcs_send_text(MAV_SEVERITY_WARNING,"No airspeed");
} }
} }

View File

@ -22,7 +22,7 @@ bool Plane::auto_takeoff_check(void)
// Reset states if process has been interrupted // Reset states if process has been interrupted
if (last_check_ms && (now - last_check_ms) > 200) { if (last_check_ms && (now - last_check_ms) > 200) {
gcs_send_text_fmt(MAV_SEVERITY_WARNING, "Timer Interrupted AUTO"); gcs_send_text_fmt(MAV_SEVERITY_WARNING, "Timer interrupted AUTO");
launchTimerStarted = false; launchTimerStarted = false;
last_tkoff_arm_time = 0; last_tkoff_arm_time = 0;
last_check_ms = now; last_check_ms = now;
@ -62,14 +62,14 @@ bool Plane::auto_takeoff_check(void)
if (ahrs.pitch_sensor <= -3000 || if (ahrs.pitch_sensor <= -3000 ||
ahrs.pitch_sensor >= 4500 || ahrs.pitch_sensor >= 4500 ||
labs(ahrs.roll_sensor) > 3000) { labs(ahrs.roll_sensor) > 3000) {
gcs_send_text_fmt(MAV_SEVERITY_WARNING, "Bad Launch AUTO"); gcs_send_text_fmt(MAV_SEVERITY_WARNING, "Bad launch AUTO");
goto no_launch; goto no_launch;
} }
// Check ground speed and time delay // Check ground speed and time delay
if (((gps.ground_speed() > g.takeoff_throttle_min_speed || is_zero(g.takeoff_throttle_min_speed))) && if (((gps.ground_speed() > g.takeoff_throttle_min_speed || is_zero(g.takeoff_throttle_min_speed))) &&
((now - last_tkoff_arm_time) >= wait_time_ms)) { ((now - last_tkoff_arm_time) >= wait_time_ms)) {
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Triggered AUTO, GPSspd = %.1f", (double)gps.ground_speed()); gcs_send_text_fmt(MAV_SEVERITY_INFO, "Triggered AUTO. GPS speed = %.1f", (double)gps.ground_speed());
launchTimerStarted = false; launchTimerStarted = false;
last_tkoff_arm_time = 0; last_tkoff_arm_time = 0;
return true; return true;