mavlink app: Be less chatty on startup

This commit is contained in:
Lorenz Meier
2015-01-09 09:09:40 +01:00
parent bb1e082781
commit d351772a46
2 changed files with 4 additions and 27 deletions
+3 -24
View File
@@ -1286,30 +1286,11 @@ Mavlink::task_main(int argc, char *argv[])
}
if (Mavlink::instance_exists(_device_name, this)) {
warnx("mavlink instance for %s already running", _device_name);
warnx("%s already running", _device_name);
return ERROR;
}
/* inform about mode */
switch (_mode) {
case MAVLINK_MODE_NORMAL:
warnx("mode: NORMAL");
break;
case MAVLINK_MODE_CUSTOM:
warnx("mode: CUSTOM");
break;
case MAVLINK_MODE_ONBOARD:
warnx("mode: ONBOARD");
break;
default:
warnx("ERROR: Unknown mode");
break;
}
warnx("data rate: %d Bytes/s, port: %s, baud: %d", _datarate, _device_name, _baudrate);
warnx("mode: %u, data rate: %d B/s on %s @ %dB", _mode, _datarate, _device_name, _baudrate);
/* flush stdout in case MAVLink is about to take it over */
fflush(stdout);
@@ -1337,7 +1318,7 @@ Mavlink::task_main(int argc, char *argv[])
* marker ring buffer approach.
*/
if (OK != message_buffer_init(2 * sizeof(mavlink_message_t) + 1)) {
errx(1, "can't allocate message buffer, exiting");
errx(1, "msg buf:");
}
/* initialize message buffer mutex */
@@ -1571,8 +1552,6 @@ Mavlink::task_main(int argc, char *argv[])
_subscriptions = nullptr;
warnx("waiting for UART receive thread");
/* wait for threads to complete */
pthread_join(_receive_thread, NULL);
+1 -3
View File
@@ -120,13 +120,11 @@ MavlinkMissionManager::init_offboard_mission()
_count = mission_state.count;
_current_seq = mission_state.current_seq;
warnx("offboard mission init: dataman_id=%d, count=%u, current_seq=%d", _dataman_id, _count, _current_seq);
} else {
_dataman_id = 0;
_count = 0;
_current_seq = 0;
warnx("offboard mission init: ERROR, reading mission state failed");
warnx("offboard mission init: ERROR");
}
}