Rover: revise text messages

Text revisions on Rover. Uniformization on messages severity.
This commit is contained in:
Luis Vale Gonçalves 2015-11-18 18:53:14 +00:00 committed by Randy Mackay
parent 6dd28f632c
commit 999e99c6f3
5 changed files with 18 additions and 18 deletions

View File

@ -878,7 +878,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) {
@ -1382,7 +1382,7 @@ void Rover::mavlink_delay_cb()
} }
if (tnow - last_5s > 5000) { if (tnow - last_5s > 5000) {
last_5s = tnow; last_5s = tnow;
gcs_send_text(MAV_SEVERITY_INFO, "Initialising APM..."); gcs_send_text(MAV_SEVERITY_INFO, "Initialising APM");
} }
check_usb_mux(); check_usb_mux();

View File

@ -30,7 +30,7 @@ void Rover::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, next_WP)) { if (location_passed_point(current_loc, prev_WP, next_WP)) {
gcs_send_text(MAV_SEVERITY_NOTICE, "Resetting prev_WP"); gcs_send_text(MAV_SEVERITY_NOTICE, "Resetting previous WP");
prev_WP = current_loc; prev_WP = current_loc;
} }
@ -63,7 +63,7 @@ void Rover::init_home()
return; return;
} }
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;

View File

@ -117,7 +117,7 @@ bool Rover::start_command(const AP_Mission::Mission_Command& cmd)
void Rover::exit_mission() void Rover::exit_mission()
{ {
if (control_mode == AUTO) { if (control_mode == AUTO) {
gcs_send_text_fmt(MAV_SEVERITY_NOTICE, "No commands. Can't set AUTO - setting HOLD"); gcs_send_text_fmt(MAV_SEVERITY_NOTICE, "No commands. Can't set AUTO. Setting HOLD");
set_mode(HOLD); set_mode(HOLD);
} }
} }
@ -164,7 +164,7 @@ bool Rover::verify_command(const AP_Mission::Mission_Command& cmd)
// this is a command that doesn't require verify // this is a command that doesn't require verify
return true; return true;
} }
gcs_send_text(MAV_SEVERITY_CRITICAL,"verify_conditon: Unsupported command"); gcs_send_text(MAV_SEVERITY_CRITICAL,"Verify conditon. Unsupported command");
return true; return true;
} }
return false; return false;
@ -203,7 +203,7 @@ bool Rover::verify_nav_wp(const AP_Mission::Mission_Command& cmd)
// Check if we need to loiter at this waypoint // Check if we need to loiter at this waypoint
if (loiter_time_max > 0) { if (loiter_time_max > 0) {
if (loiter_time == 0) { // check if we are just starting loiter if (loiter_time == 0) { // check if we are just starting loiter
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Reached Waypoint #%i - Loiter for %i seconds", gcs_send_text_fmt(MAV_SEVERITY_INFO, "Reached waypoint #%i. Loiter for %i seconds",
(unsigned)cmd.index, (unsigned)cmd.index,
(unsigned)loiter_time_max); (unsigned)loiter_time_max);
// record the current time i.e. start timer // record the current time i.e. start timer
@ -214,7 +214,7 @@ bool Rover::verify_nav_wp(const AP_Mission::Mission_Command& cmd)
return false; return false;
} }
} else { } else {
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Reached Waypoint #%i dist %um", gcs_send_text_fmt(MAV_SEVERITY_INFO, "Reached waypoint #%i. Distance %um",
(unsigned)cmd.index, (unsigned)cmd.index,
(unsigned)get_distance(current_loc, next_WP)); (unsigned)get_distance(current_loc, next_WP));
} }
@ -228,7 +228,7 @@ bool Rover::verify_nav_wp(const AP_Mission::Mission_Command& cmd)
// check if we have gone futher past the wp then last time and output new message if we have // check if we have gone futher past the wp then last time and output new message if we have
if ((uint32_t)distance_past_wp != (uint32_t)get_distance(current_loc, next_WP)) { if ((uint32_t)distance_past_wp != (uint32_t)get_distance(current_loc, next_WP)) {
distance_past_wp = get_distance(current_loc, next_WP); distance_past_wp = get_distance(current_loc, next_WP);
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Passed Waypoint #%i dist %um", gcs_send_text_fmt(MAV_SEVERITY_INFO, "Passed waypoint #%i. Distance %um",
(unsigned)cmd.index, (unsigned)cmd.index,
(unsigned)distance_past_wp); (unsigned)distance_past_wp);
} }
@ -248,14 +248,14 @@ bool Rover::verify_nav_wp(const AP_Mission::Mission_Command& cmd)
bool Rover::verify_RTL() bool Rover::verify_RTL()
{ {
if (wp_distance <= g.waypoint_radius) { if (wp_distance <= g.waypoint_radius) {
gcs_send_text(MAV_SEVERITY_INFO,"Reached Destination"); gcs_send_text(MAV_SEVERITY_INFO,"Reached destination");
rtl_complete = true; rtl_complete = true;
return true; return true;
} }
// have we gone past the waypoint? // have we gone past the waypoint?
if (location_passed_point(current_loc, prev_WP, next_WP)) { if (location_passed_point(current_loc, prev_WP, next_WP)) {
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Reached Destination: Distance away %um", gcs_send_text_fmt(MAV_SEVERITY_INFO, "Reached destination. Distance away %um",
(unsigned)get_distance(current_loc, next_WP)); (unsigned)get_distance(current_loc, next_WP));
rtl_complete = true; rtl_complete = true;
return true; return true;

View File

@ -6,7 +6,7 @@ void Rover::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 Rover::init_sonar(void) void Rover::init_sonar(void)
@ -83,7 +83,7 @@ void Rover::read_sonars(void)
obstacle.detected_count++; obstacle.detected_count++;
} }
if (obstacle.detected_count == g.sonar_debounce) { if (obstacle.detected_count == g.sonar_debounce) {
gcs_send_text_fmt(MAV_SEVERITY_NOTICE, "Sonar obstacle %u cm", gcs_send_text_fmt(MAV_SEVERITY_INFO, "Sonar obstacle %u cm",
(unsigned)obstacle.sonar1_distance_cm); (unsigned)obstacle.sonar1_distance_cm);
} }
obstacle.detected_time_ms = AP_HAL::millis(); obstacle.detected_time_ms = AP_HAL::millis();

View File

@ -214,10 +214,10 @@ void Rover::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
@ -241,7 +241,7 @@ void Rover::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 drive."); gcs_send_text(MAV_SEVERITY_INFO,"Ready to drive");
} }
/* /*
@ -384,12 +384,12 @@ void Rover::failsafe_trigger(uint8_t failsafe_type, bool on)
void Rover::startup_INS_ground(void) void Rover::startup_INS_ground(void)
{ {
gcs_send_text(MAV_SEVERITY_INFO, "Warming up ADC..."); gcs_send_text(MAV_SEVERITY_INFO, "Warming up ADC");
mavlink_delay(500); mavlink_delay(500);
// Makes the servos wiggle twice - about to begin INS calibration - HOLD LEVEL AND STILL!! // Makes the servos wiggle twice - about to begin INS calibration - HOLD LEVEL AND STILL!!
// ----------------------- // -----------------------
gcs_send_text(MAV_SEVERITY_INFO, "Beginning INS calibration; do not move vehicle"); gcs_send_text(MAV_SEVERITY_INFO, "Beginning INS calibration. Do not move vehicle");
mavlink_delay(1000); mavlink_delay(1000);
ahrs.init(); ahrs.init();