Skip to content
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

Serial1.flush() - I believe is doing the old behaviour and output buffers? #28

Closed
KurtE opened this issue Jul 24, 2018 · 10 comments
Closed
Assignees
Labels

Comments

@KurtE
Copy link
Contributor

KurtE commented Jul 24, 2018

Prior to Arduino 1.0, Serial1.flush() would throw away all of the buffered input.

Where as after that Serial1.flush() would wait for all buffered output to fully go out the device as you can see in the Arduino reference: https://www.arduino.cc/reference/en/language/functions/communication/serial/flush/

Looking at the Sources:
UARTClass.cpp:

void UARTClass::flush( void )
{
  drv_uart_flush(_uart_num);
}

Which if you look in drv_uart.c you see:

void drv_uart_flush(uint8_t uart_num)
{
  if(is_uart_mode[uart_num] == DRV_UART_IRQ_MODE)
  {
    drv_uart_rx_buf_head[uart_num] = 0;
    drv_uart_rx_buf_tail[uart_num] = 0;
  }
  else
  {
    drv_uart_rx_buf_head[uart_num] = DRV_UART_RX_BUF_LENGTH - hdma_rx[uart_num].Instance->CNDTR;
    drv_uart_rx_buf_tail[uart_num] = drv_uart_rx_buf_head[uart_num];
  }
}

Note: reading through sources, I am unsure if you need a new Arduino flush behavior?
That is typically on Arduino if you do something like:

Serail1.write(0);
or
Serial1.write(Buffer, cnt);

The call would the majority of time simply put the data into an output buffer and return immediately. The exception, is if you tried to write more data into the queue than what would fit, in which case the call would not return until enough data was sent that the last parts of your write would fit into buffer.

That is why some platforms have also added call: Serial1.availableForWrite(), which would give you the current free space on the output buffer, such that you could than write less than that and know you were not going to block.

The reason I noticed this was looking at DynamixelSDK port_handler_arduino.cpp at:

int PortHandlerArduino::writePort(uint8_t *packet, int length)
{
  int length_written;

  setTxEnable();

#if defined(__OPENCR__)
  length_written = DYNAMIXEL_SERIAL.write(packet, length);
#elif defined(__OPENCM904__)
  length_written = p_dxl_serial->write(packet, length);
#endif

  setTxDisable();

  return length_written;
}

The setTxEnable() and setTxDisable(), just set the appropriate IO port for the correct direction. So was unclear how the underlying call p_dxl_Serial->write on who waited for the underlying call:
Serial1.write(packet, length) to complete...

Not sure how much should change here... But for example I do have code that does use things like:

Serial1.print(....)
Seriall1.flush(); // wait for data output to complete..

EDIT: noticed you do have Serial1.availableForWrite, but not sure it is correct?

int UARTClass::availableForWrite(void)
{
  return drv_uart_tx_available(_uart_num);
}

Where:

uint32_t drv_uart_tx_available(uint8_t uart_num)
{
  uint32_t length;


  length = DRV_UART_RX_BUF_LENGTH - drv_uart_available(uart_num) - 1;

  return length;
}

Which appears to be dealing with RX queue, not the TX...

@OpusK
Copy link
Contributor

OpusK commented Jul 25, 2018

@KurtE,
Thanks for your report :)

you're right.
OpenCM confirmed that the function name and the actual operation are inconsistent, and that OpenCR is not implemented.

I will commit in this regard.

OpusK pushed a commit that referenced this issue Jul 25, 2018
@OpusK
Copy link
Contributor

OpusK commented Jul 25, 2018

I erased the wrong code.
But, I checked that OpenCM USART TX is using polling method.

Since the flush function is only meaningful for DMA or Interrupt, we will modify the flush function accordingly if we change the TX function later.

@KurtE
Copy link
Contributor Author

KurtE commented Jul 25, 2018

@OpusK,
Thanks,

Probably goes without saying, but the difficult part of this change is that there is probably other code that relies on the old semantics of flush().

Example in dynamixel_sdkthe file port_handler_arduino.cpp there is a function PortHandlerArduino::clearPort(), which calls flush, expecting to clear out anything that was queued...

Note; on Teensy 3.x boards, the serial class has an additional method clear(), which is probably non-standard which does what the old flush did...

@OpusK
Copy link
Contributor

OpusK commented Jul 25, 2018

@KurtE,

Example in dynamixel_sdkthe file port_handler_arduino.cpp there is a function PortHandlerArduino::clearPort(), which calls flush, expecting to clear out anything that was queued...

The original meaning of the code is to clear the TX buffer. However, since DXL uses UART only, it follows the polling function of OpenCM UARTClass::write() function and does not use a separate internal buffer.
If there is a buffer used internally for TX, DMA, or interrupt, we must implement the function to clear all TX buffers. But OpenCM is not the same.

Therefore, there is no buffer to clear, and it seems that there will be no problem in using this modified code.

Please let me know if I misunderstand this :)

@KurtE
Copy link
Contributor Author

KurtE commented Jul 25, 2018

@OpusK,

Hard for me to say, what the semantics you are expecting here. For example in my own dynamixel library, when I am sending packets, I do both, example:
https://github.com/KurtE/BioloidSerial/blob/DXL-Protocol-2-Test/dxlSerial.cpp#L212

And if I look at your other implementations for the PortHandler?::clearPort, you see:

void PortHandlerLinux::clearPort()
{
  tcflush(socket_fd_, TCIOFLUSH);
}
void PortHandlerMac::clearPort()
{
  tcflush(socket_fd_, TCIOFLUSH);
}

void PortHandlerWindows::clearPort()
{
  PurgeComm(serial_handle_, PURGE_RXABORT | PURGE_RXCLEAR);
}

So the Linux and Mac, it clears both TX and RX and it looks like on Windows it clears RX...

So your guess is as good as mine, what is actually needed here.

(Edited) - cut and pasted wrong linux function

@OpusK
Copy link
Contributor

OpusK commented Jul 26, 2018

@KurtE

Oh, now I understand what you are saying.
As you have seen, clearing the port just before DXL TX seems to clear the RX buffer, not only because of the TX buffer, but also because the user has not acknowledged the response data from the previous TX command.

So, as you say, we need to create a separate function that can clear the RX buffer and call it in clearPort ().

Thank you :)

OpusK pushed a commit that referenced this issue Jul 26, 2018
@KurtE
Copy link
Contributor Author

KurtE commented Jul 26, 2018

Looks good!

@OpusK
Copy link
Contributor

OpusK commented Jul 26, 2018

@KurtE

Later, when using DMA mode, it was treated as simply reading the data with a timeout in consideration of the buffer synchronization problem.

Please let me know if you have a better idea :)
If you do not mind, can I close this issue?

@KurtE
Copy link
Contributor Author

KurtE commented Jul 27, 2018

@OpusK - as you said, I believe you have addressed the issue. If at some point DMA or interrupt mode is implemented and an Output buffer is defined and used, than the new flush behavior sound be implemented at that time.

So I agree with you that this issue should be closed

@OpusK
Copy link
Contributor

OpusK commented Jul 27, 2018

@KurtE - Thanks for your feedback :)

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

No branches or pull requests

3 participants