Skip to content

Commit

Permalink
AP_ExternalAHRS: VectorNav: Disable ASCII messages on both ports, rat…
Browse files Browse the repository at this point in the history
…her than just active port

This change prevents a commonly seen baudrate overflow error on the unused port.
Also pause asynchronous communications during initial configuration.
  • Loading branch information
lashVN committed Jul 5, 2024
1 parent 24da8e7 commit 0f39760
Showing 1 changed file with 12 additions and 1 deletion.
13 changes: 12 additions & 1 deletion libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -405,7 +405,15 @@ void AP_ExternalAHRS_VectorNav::initialize() {
// Open port in the thread
uart->begin(baudrate, 1024, 512);

hal.util->snprintf(message_to_send, sizeof(message_to_send), "VNWRG,06,0");
// Pause asynchronous communications to simplify packet finding
hal.util->snprintf(message_to_send, sizeof(message_to_send), "$VNASY,0");
send_command_blocking();

// Stop ASCII async outputs for both UARTs. If only active UART is disabled, we get a baudrate
// overflow on the other UART when configuring binary outputs (reg 75 and 76) to both UARTs
hal.util->snprintf(message_to_send, sizeof(message_to_send), "VNWRG,06,1");
send_command_blocking();
hal.util->snprintf(message_to_send, sizeof(message_to_send), "VNWRG,06,2");
send_command_blocking();

// Read Model Number Register, ID 1
Expand Down Expand Up @@ -439,6 +447,9 @@ void AP_ExternalAHRS_VectorNav::initialize() {
send_command_blocking();
}

// Resume asynchronous communications
hal.util->snprintf(message_to_send, sizeof(message_to_send), "$VNASY,1\0");
send_command_blocking();
setup_complete = true;
}

Expand Down

0 comments on commit 0f39760

Please sign in to comment.