Copter: Delete the last newline of the message.

This commit is contained in:
murata 2018-11-07 01:25:03 +09:00 committed by Randy Mackay
parent 48610ea0a0
commit 7a3f84566a

View File

@ -709,7 +709,7 @@ void ToyMode::trim_update(void)
int16_t new_value = 1000UL * (throttle_trim - ch_min) / (ch_max - ch_min);
if (new_value != throttle_mid) {
throttle_mid = new_value;
gcs().send_text(MAV_SEVERITY_ERROR, "Tmode: thr mid %d\n",
gcs().send_text(MAV_SEVERITY_ERROR, "Tmode: thr mid %d",
throttle_mid);
}
}
@ -773,7 +773,7 @@ void ToyMode::trim_update(void)
}
}
gcs().send_text(MAV_SEVERITY_ERROR, "Tmode: trim %u %u %u %u\n",
gcs().send_text(MAV_SEVERITY_ERROR, "Tmode: trim %u %u %u %u",
chan[0], chan[1], chan[2], chan[3]);
}
@ -792,7 +792,7 @@ void ToyMode::action_arm(void)
copter.channel_yaw->get_control_in() == 0;
if (!sticks_centered) {
gcs().send_text(MAV_SEVERITY_ERROR, "Tmode: sticks not centered\n");
gcs().send_text(MAV_SEVERITY_ERROR, "Tmode: sticks not centered");
return;
}