forked from Archive/PX4-Autopilot
mavlink: Fix setting MAV_SIK_RADIO_ID
The AT commands were formatted incorrectly
This commit is contained in:
parent
2cb4ef0629
commit
cce3b43b4f
|
@ -2746,26 +2746,27 @@ void Mavlink::configure_sik_radio()
|
|||
if (fs) {
|
||||
/* switch to AT command mode */
|
||||
px4_usleep(1200000);
|
||||
fprintf(fs, "+++\n");
|
||||
fprintf(fs, "+++");
|
||||
fflush(fs);
|
||||
px4_usleep(1200000);
|
||||
|
||||
if (_param_sik_radio_id.get() > 0) {
|
||||
/* set channel */
|
||||
fprintf(fs, "ATS3=%" PRIu32 "\n", _param_sik_radio_id.get());
|
||||
fprintf(fs, "ATS3=%" PRIu32 "\r\n", _param_sik_radio_id.get());
|
||||
px4_usleep(200000);
|
||||
|
||||
} else {
|
||||
/* reset to factory defaults */
|
||||
fprintf(fs, "AT&F\n");
|
||||
fprintf(fs, "AT&F\r\n");
|
||||
px4_usleep(200000);
|
||||
}
|
||||
|
||||
/* write config */
|
||||
fprintf(fs, "AT&W");
|
||||
fprintf(fs, "AT&W\r\n");
|
||||
px4_usleep(200000);
|
||||
|
||||
/* reboot */
|
||||
fprintf(fs, "ATZ");
|
||||
fprintf(fs, "ATZ\r\n");
|
||||
px4_usleep(200000);
|
||||
|
||||
// XXX NuttX suffers from a bug where
|
||||
|
|
Loading…
Reference in New Issue