Skip to content

Commit 2dccd6c

Browse files
authored
Voxl ESC driver update (#23022)
* Made Serial API open the UART in NON BLOCKING mode * Updated voxl_esc driver to latest from ModalAI fork * Ported voxl_esc driver over to new Serial UART API * Removed voxl_esc serial abstraction since new Serial API is already a serial abstraction
1 parent a8a67fb commit 2dccd6c

File tree

12 files changed

+352
-400
lines changed

12 files changed

+352
-400
lines changed

platforms/common/include/px4_platform_common/Serial.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -55,6 +55,7 @@ class Serial
5555
virtual ~Serial();
5656

5757
// Open sets up the port and gets it configured based on desired configuration
58+
// The port is always opened in NON BLOCKING mode.
5859
bool open();
5960
bool isOpen() const;
6061

platforms/nuttx/src/px4/common/SerialImpl.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -181,7 +181,7 @@ bool SerialImpl::open()
181181
}
182182

183183
// Open the serial port
184-
int serial_fd = ::open(_port, O_RDWR | O_NOCTTY);
184+
int serial_fd = ::open(_port, O_RDWR | O_NOCTTY | O_NONBLOCK);
185185

186186
if (serial_fd < 0) {
187187
PX4_ERR("failed to open %s err: %d", _port, errno);

platforms/nuttx/src/px4/common/include/SerialImpl.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -114,6 +114,7 @@ class SerialImpl
114114
bool _single_wire_mode{false};
115115
bool _swap_rx_tx_mode{false};
116116
bool _inverted_mode{false};
117+
117118
};
118119

119120
} // namespace device

platforms/posix/include/SerialImpl.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -114,6 +114,7 @@ class SerialImpl
114114
bool _single_wire_mode{false};
115115
bool _swap_rx_tx_mode{false};
116116
bool _inverted_mode{false};
117+
117118
};
118119

119120
} // namespace device

platforms/posix/src/px4/common/SerialImpl.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -179,7 +179,7 @@ bool SerialImpl::open()
179179
}
180180

181181
// Open the serial port
182-
int serial_fd = ::open(_port, O_RDWR | O_NOCTTY);
182+
int serial_fd = ::open(_port, O_RDWR | O_NOCTTY | O_NONBLOCK);
183183

184184
if (serial_fd < 0) {
185185
PX4_ERR("failed to open %s err: %d", _port, errno);

platforms/qurt/src/px4/SerialImpl.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -163,7 +163,7 @@ ssize_t SerialImpl::read(uint8_t *buffer, size_t buffer_size)
163163
return -1;
164164
}
165165

166-
int ret_read = qurt_uart_read(_serial_fd, (char *) buffer, buffer_size, 500);
166+
int ret_read = qurt_uart_read(_serial_fd, (char *) buffer, buffer_size, 100);
167167

168168
if (ret_read < 0) {
169169
PX4_DEBUG("%s read error %d", _port, ret_read);

src/drivers/actuators/voxl_esc/CMakeLists.txt

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -38,8 +38,6 @@ px4_add_module(
3838
crc16.c
3939
crc16.h
4040

41-
voxl_esc_serial.cpp
42-
voxl_esc_serial.hpp
4341
voxl_esc.cpp
4442
voxl_esc.hpp
4543
qc_esc_packet_types.h

0 commit comments

Comments
 (0)