AP_HAL_Linux: CAN: get rid of RaiiCloser

This commit is contained in:
Nikita Tomilov 2017-12-28 11:37:15 +03:00 committed by Tom Pittenger
parent 976500960f
commit b6665f7e58

View File

@ -119,26 +119,13 @@ int LinuxCAN::openSocket(const std::string& iface_name)
{ {
errno = 0; errno = 0;
const int s = socket(PF_CAN, SOCK_RAW, CAN_RAW); int s = socket(PF_CAN, SOCK_RAW, CAN_RAW);
if (s < 0) { if (s < 0) {
return s; return s;
} }
class RaiiCloser std::shared_ptr<void> defer(&s, [](int* fd) { if (*fd >= 0) close(*fd); });
{ const int ret = s;
int fd_;
public:
RaiiCloser(int filedesc) : fd_(filedesc)
{ }
~RaiiCloser()
{
if (fd_ >= 0) {
hal.console->printf("SocketCAN: closing fd\n");
close(fd_);
}
}
void disarm() { fd_ = -1; }
} raii_closer(s);
// Detect the iface index // Detect the iface index
auto ifr = ifreq(); auto ifr = ifreq();
@ -188,9 +175,8 @@ int LinuxCAN::openSocket(const std::string& iface_name)
return -1; return -1;
} }
} }
s = -1;
raii_closer.disarm(); return ret;
return s;
} }
int16_t LinuxCAN::send(const uavcan::CanFrame& frame, const uavcan::MonotonicTime tx_deadline, int16_t LinuxCAN::send(const uavcan::CanFrame& frame, const uavcan::MonotonicTime tx_deadline,