|
|
|
@ -29,38 +29,8 @@ using namespace SITL;
@@ -29,38 +29,8 @@ using namespace SITL;
|
|
|
|
|
|
|
|
|
|
SerialDevice::SerialDevice() |
|
|
|
|
{ |
|
|
|
|
// pipe for device to write to:
|
|
|
|
|
int tmp[2]; |
|
|
|
|
if (pipe(tmp) == -1) { |
|
|
|
|
AP_HAL::panic("pipe() failed"); |
|
|
|
|
} |
|
|
|
|
fd_my_end = tmp[1]; |
|
|
|
|
fd_their_end = tmp[0]; |
|
|
|
|
|
|
|
|
|
// close file descriptors on exec:
|
|
|
|
|
fcntl(fd_my_end, F_SETFD, FD_CLOEXEC); |
|
|
|
|
fcntl(fd_their_end, F_SETFD, FD_CLOEXEC); |
|
|
|
|
|
|
|
|
|
// make sure we don't screw the simulation up by blocking:
|
|
|
|
|
fcntl(fd_my_end, F_SETFL, fcntl(fd_my_end, F_GETFL, 0) | O_NONBLOCK); |
|
|
|
|
fcntl(fd_their_end, F_SETFL, fcntl(fd_their_end, F_GETFL, 0) | O_NONBLOCK); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// pipe for device to read from:
|
|
|
|
|
if (pipe(tmp) == -1) { |
|
|
|
|
AP_HAL::panic("pipe() failed"); |
|
|
|
|
} |
|
|
|
|
read_fd_my_end = tmp[0]; |
|
|
|
|
read_fd_their_end = tmp[1]; |
|
|
|
|
|
|
|
|
|
// close file descriptors on exec:
|
|
|
|
|
fcntl(read_fd_my_end, F_SETFD, FD_CLOEXEC); |
|
|
|
|
fcntl(read_fd_their_end, F_SETFD, FD_CLOEXEC); |
|
|
|
|
|
|
|
|
|
// make sure we don't screw the simulation up by blocking:
|
|
|
|
|
fcntl(read_fd_my_end, F_SETFL, fcntl(fd_my_end, F_GETFL, 0) | O_NONBLOCK); |
|
|
|
|
fcntl(read_fd_their_end, F_SETFL, fcntl(fd_their_end, F_GETFL, 0) | O_NONBLOCK); |
|
|
|
|
|
|
|
|
|
to_autopilot = new ByteBuffer{512}; |
|
|
|
|
from_autopilot = new ByteBuffer{512}; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
bool SerialDevice::init_sitl_pointer() |
|
|
|
@ -74,10 +44,9 @@ bool SerialDevice::init_sitl_pointer()
@@ -74,10 +44,9 @@ bool SerialDevice::init_sitl_pointer()
|
|
|
|
|
return true; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
ssize_t SerialDevice::read_from_autopilot(char *buffer, const size_t size) const |
|
|
|
|
{ |
|
|
|
|
const ssize_t ret = ::read(read_fd_my_end, buffer, size); |
|
|
|
|
const ssize_t ret = from_autopilot->read((uint8_t*)buffer, size); |
|
|
|
|
// if (ret > 0) {
|
|
|
|
|
// ::fprintf(stderr, "SIM_SerialDevice: read from autopilot (%u): (", (unsigned)ret);
|
|
|
|
|
// for (ssize_t i=0; i<ret; i++) {
|
|
|
|
@ -95,7 +64,7 @@ ssize_t SerialDevice::read_from_autopilot(char *buffer, const size_t size) const
@@ -95,7 +64,7 @@ ssize_t SerialDevice::read_from_autopilot(char *buffer, const size_t size) const
|
|
|
|
|
|
|
|
|
|
ssize_t SerialDevice::write_to_autopilot(const char *buffer, const size_t size) const |
|
|
|
|
{ |
|
|
|
|
const ssize_t ret = write(fd_my_end, buffer, size); |
|
|
|
|
const ssize_t ret = to_autopilot->write((uint8_t*)buffer, size); |
|
|
|
|
// ::fprintf(stderr, "write to autopilot: (");
|
|
|
|
|
// for (ssize_t i=0; i<ret; i++) {
|
|
|
|
|
// ::fprintf(stderr, "%02X", (uint8_t)buffer[i]);
|
|
|
|
@ -107,3 +76,14 @@ ssize_t SerialDevice::write_to_autopilot(const char *buffer, const size_t size)
@@ -107,3 +76,14 @@ ssize_t SerialDevice::write_to_autopilot(const char *buffer, const size_t size)
|
|
|
|
|
// ::fprintf(stderr, ")\n");
|
|
|
|
|
return ret; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
ssize_t SerialDevice::read_from_device(char *buffer, const size_t size) const |
|
|
|
|
{ |
|
|
|
|
const ssize_t ret = to_autopilot->read((uint8_t*)buffer, size); |
|
|
|
|
return ret; |
|
|
|
|
} |
|
|
|
|
ssize_t SerialDevice::write_to_device(const char *buffer, const size_t size) const |
|
|
|
|
{ |
|
|
|
|
const ssize_t ret = from_autopilot->write((uint8_t*)buffer, size); |
|
|
|
|
return ret; |
|
|
|
|
} |
|
|
|
|