Skip to content

ChibiOS: UARTDriver: init dma buffer #30023

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Open
wants to merge 1 commit into
base: master
Choose a base branch
from

Conversation

pshavoc
Copy link

@pshavoc pshavoc commented May 9, 2025

this change initializes the UART DMA buffers properly and also respects the OPTION_NODMA_RX and OPTION_NODMA_TX options.

@tpwrules
Copy link
Contributor

Thanks for the contribution. Are you seeing an issue caused by this? ArduPilot zeros memory on allocation so member variables are assumed initialized.

@pshavoc
Copy link
Author

pshavoc commented May 12, 2025

I was finding that the driver was always using DMA for receiving data, even when I set the OPTION_NODMA_RX option flag. I traced this down to this line and found that rx_dma_enabled was always true. I then added the code to initialize rx_bounce_buf to nullptr and that fixed the problem.

@tpwrules
Copy link
Contributor

What board and compiler?

@pshavoc
Copy link
Author

pshavoc commented May 12, 2025

CubeOrangePlus, arm-none-eabi-gcc (GNU Arm Embedded Toolchain 10-2020-q4-major) 10.2.1 20201103 (release)

Copy link
Contributor

@andyp1per andyp1per left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Good catch! Only the second change is required I believe

@@ -107,6 +107,9 @@ _baudrate(57600)
{
osalDbgAssert(serial_num < UART_MAX_DRIVERS, "too many SERIALn drivers");
serial_drivers[serial_num] = this;
rx_bounce_buf[0] = nullptr;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Please remove these, they are not necessary

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I believe it is necessary for correctly handling the case when the user intends to use DMA. Without it, rx_bounce_buf[0] could be non-null. This if case would fail and therefor the malloc_type would be skipped. Thats def bad.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Unless someone is creating one of these UARTDriver objects on the stack, all member fields are guaranteed zero in the constructor. We override new to get that effect.

If someone is creating one of these on the stack... well...

@andyp1per andyp1per added the BUG label May 24, 2025
Copy link
Contributor

@peterbarker peterbarker left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This looks like a useful fix. Please remove the lines which shouldn't be needed. If you find they are needed we have serious problems :-)

@@ -107,6 +107,9 @@ _baudrate(57600)
{
osalDbgAssert(serial_num < UART_MAX_DRIVERS, "too many SERIALn drivers");
serial_drivers[serial_num] = this;
rx_bounce_buf[0] = nullptr;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Unless someone is creating one of these UARTDriver objects on the stack, all member fields are guaranteed zero in the constructor. We override new to get that effect.

If someone is creating one of these on the stack... well...

@pshavoc
Copy link
Author

pshavoc commented May 29, 2025

@peterbarker ok removed now

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Projects
Development

Successfully merging this pull request may close these issues.

4 participants