19 #if defined(__APPLE__) 28 #include <sys/ioctl.h> 31 #include <mach/clock.h> 32 #include <mach/mach.h> 37 #define LATENCY_TIMER 16 // msec (USB latency timer) 50 baudrate_(DEFAULT_BAUDRATE_),
51 packet_start_time_(0.0),
114 ioctl(
socket_fd_, FIONREAD, &bytes_available);
115 return bytes_available;
153 #ifdef __MACH__ // OS X does not have clock_gettime, so here uses clock_get_time 156 host_get_clock_service(mach_host_self(), CALENDAR_CLOCK, &cclock);
157 clock_get_time(cclock, &mts);
158 mach_port_deallocate(mach_task_self(), cclock);
159 tv.tv_sec = mts.tv_sec;
160 tv.tv_nsec = mts.tv_nsec;
162 clock_gettime(CLOCK_REALTIME, &tv);
164 return ((
double)tv.tv_sec * 1000.0 + (
double)tv.tv_nsec * 0.001 * 0.001);
180 struct termios newtio;
185 printf(
"[PortHandlerMac::SetupPort] Error opening serial port!\n");
189 bzero(&newtio,
sizeof(newtio));
191 newtio.c_cflag = CS8 | CLOCAL | CREAD;
192 newtio.c_iflag = IGNPAR;
195 newtio.c_cc[VTIME] = 0;
196 newtio.c_cc[VMIN] = 0;
197 cfsetispeed(&newtio, cflag_baud);
198 cfsetospeed(&newtio, cflag_baud);
201 tcflush(socket_fd_, TCIFLUSH);
202 tcsetattr(socket_fd_, TCSANOW, &newtio);
210 printf(
"[PortHandlerMac::SetCustomBaudrate] Not supported on Mac!\n");
bool setCustomBaudrate(int speed)
bool setBaudRate(const int baudrate)
The function that sets baudrate into the port handler The function sets baudrate into the port handl...
void setPortName(const char *port_name)
The function that sets port name into the port handler The function sets port name into the port han...
bool setBaudRate(const int baudrate)
The function that sets baudrate into the port handler The function sets baudrate into the port handl...
bool openPort()
The function that opens the port The function calls PortHandlerMac::setBaudRate() to open the port...
double packet_start_time_
char * getPortName()
The function that returns port name set into the port handler The function returns current port name...
PortHandlerMac(const char *port_name)
The function that initializes instance of PortHandler and gets port_name The function initializes in...
bool setupPort(const int cflag_baud)
void closePort()
The function that closes the port The function closes the port.
int readPort(uint8_t *packet, int length)
The function that reads bytes from the port buffer The function gets bytes from the port buffer...
bool isPacketTimeout()
The function that checks whether packet timeout is occurred The function checks whether current time...
void setPacketTimeout(uint16_t packet_length)
The function that sets and starts stopwatch for watching packet timeout The function sets the stopwa...
int getCFlagBaud(const int baudrate)
int writePort(uint8_t *packet, int length)
The function that writes bytes on the port buffer The function writes bytes on the port buffer...
void closePort()
The function that closes the port The function closes the port.
bool setCustomBaudrate(int speed)
int getBytesAvailable()
The function that checks how much bytes are able to be read from the port buffer The function checks...
void setPortName(const char *port_name)
The function that sets port name into the port handler The function sets port name into the port han...
void clearPort()
The function that clears the port The function clears the port.
int getCFlagBaud(const int baudrate)
int getBaudRate()
The function that returns current baudrate set into the port handler The function returns current ba...
bool is_using_
shows whether the port is in use
double getTimeSinceStart()
double getTimeSinceStart()
bool setupPort(const int cflag_baud)