Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions platforms/common/include/px4_platform_common/Serial.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,7 @@ class Serial
virtual ~Serial();

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

Expand Down
2 changes: 1 addition & 1 deletion platforms/nuttx/src/px4/common/SerialImpl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -181,7 +181,7 @@ bool SerialImpl::open()
}

// Open the serial port
int serial_fd = ::open(_port, O_RDWR | O_NOCTTY);
int serial_fd = ::open(_port, O_RDWR | O_NOCTTY | O_NONBLOCK);

if (serial_fd < 0) {
PX4_ERR("failed to open %s err: %d", _port, errno);
Expand Down
1 change: 1 addition & 0 deletions platforms/nuttx/src/px4/common/include/SerialImpl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -114,6 +114,7 @@ class SerialImpl
bool _single_wire_mode{false};
bool _swap_rx_tx_mode{false};
bool _inverted_mode{false};

};

} // namespace device
1 change: 1 addition & 0 deletions platforms/posix/include/SerialImpl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -114,6 +114,7 @@ class SerialImpl
bool _single_wire_mode{false};
bool _swap_rx_tx_mode{false};
bool _inverted_mode{false};

};

} // namespace device
2 changes: 1 addition & 1 deletion platforms/posix/src/px4/common/SerialImpl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -179,7 +179,7 @@ bool SerialImpl::open()
}

// Open the serial port
int serial_fd = ::open(_port, O_RDWR | O_NOCTTY);
int serial_fd = ::open(_port, O_RDWR | O_NOCTTY | O_NONBLOCK);

if (serial_fd < 0) {
PX4_ERR("failed to open %s err: %d", _port, errno);
Expand Down
2 changes: 1 addition & 1 deletion platforms/qurt/src/px4/SerialImpl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -163,7 +163,7 @@ ssize_t SerialImpl::read(uint8_t *buffer, size_t buffer_size)
return -1;
}

int ret_read = qurt_uart_read(_serial_fd, (char *) buffer, buffer_size, 500);
int ret_read = qurt_uart_read(_serial_fd, (char *) buffer, buffer_size, 100);

if (ret_read < 0) {
PX4_DEBUG("%s read error %d", _port, ret_read);
Expand Down
2 changes: 0 additions & 2 deletions src/drivers/actuators/voxl_esc/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -38,8 +38,6 @@ px4_add_module(
crc16.c
crc16.h

voxl_esc_serial.cpp
voxl_esc_serial.hpp
voxl_esc.cpp
voxl_esc.hpp
qc_esc_packet_types.h
Expand Down
Loading