Go to the documentation of this file.
   32     tcflush(serial->
fd, TCIOFLUSH);
 
   46     enum { O_EXLOCK = 0x0 }; 
 
   48     serial->
fd = open(device, O_RDWR | O_EXLOCK | O_NONBLOCK | O_NOCTTY);
 
   55     flags = fcntl(serial->
fd, F_GETFL, 0);
 
   56     fcntl(serial->
fd, F_SETFL, flags & ~O_NONBLOCK);
 
   59     tcgetattr(serial->
fd, &serial->
sio);
 
   60     serial->
sio.c_iflag = 0;
 
   61     serial->
sio.c_oflag = 0;
 
   62     serial->
sio.c_cflag &= ~(CSIZE | PARENB | CSTOPB);
 
   63     serial->
sio.c_cflag |= CS8 | CREAD | CLOCAL;
 
   64     serial->
sio.c_lflag &= ~(ICANON | ECHO | ISIG | IEXTEN);
 
   66     serial->
sio.c_cc[VMIN] = 0;
 
   67     serial->
sio.c_cc[VTIME] = 0;
 
   84     if (serial->
fd >= 0) {
 
   93     long baudrate_value = -1;
 
   97         baudrate_value = B4800;
 
  101         baudrate_value = B9600;
 
  105         baudrate_value = B19200;
 
  109         baudrate_value = B38400;
 
  113         baudrate_value = B57600;
 
  117         baudrate_value = B115200;
 
  125     cfsetospeed(&serial->
sio, baudrate_value);
 
  126     cfsetispeed(&serial->
sio, baudrate_value);
 
  127     tcsetattr(serial->
fd, TCSADRAIN, &serial->
sio);
 
  139     return write(serial->
fd, data, size);
 
  150     FD_SET(serial->
fd, &rfds);
 
  152     tv.tv_sec = timeout / 1000;
 
  153     tv.tv_usec = (timeout % 1000) * 1000;
 
  155     if (select(serial->
fd + 1, &rfds, NULL, NULL,
 
  156                (timeout < 0) ? NULL : &tv) <= 0) {
 
  169     if (data_size_max <= 0) {
 
  173     while (filled < data_size_max) {
 
  181         require_n = data_size_max - filled;
 
  182         read_n = read(serial->
fd, &data[filled], require_n);
 
  218     read_n = max_size - filled;
 
  219     if (buffer_size < read_n) {
 
  232     if (read_n > buffer_size) {
 
  233         read_n = buffer_size;
 
  
int serial_set_baudrate(urg_serial_t *serial, long baudrate)
ボーレートを設定する
int ring_read(ring_buffer_t *ring, char *buffer, int size)
データの取り出し
static int internal_receive(char data[], int data_size_max, urg_serial_t *serial, int timeout)
static int wait_receive(urg_serial_t *serial, int timeout)
void serial_close(urg_serial_t *serial)
接続を閉じる
void ring_initialize(ring_buffer_t *ring, char *buffer, const int shift_length)
初期化
static void serial_clear(urg_serial_t *serial)
static void serial_initialize(urg_serial_t *serial)
int ring_write(ring_buffer_t *ring, const char *data, int size)
データの格納
char buffer[RING_BUFFER_SIZE]
void ring_clear(ring_buffer_t *ring)
リングバッファのクリア
int serial_write(urg_serial_t *serial, const char *data, int size)
データを送信する
int serial_read(urg_serial_t *serial, char *data, int max_size, int timeout)
データを受信する
int ring_capacity(const ring_buffer_t *ring)
最大の格納データ数を返す
int serial_open(urg_serial_t *serial, const char *device, long baudrate)
接続を開く
int ring_size(const ring_buffer_t *ring)
格納データ数を返す
urg_c
Author(s): Satofumi Kamimura 
, Katsumi Kimoto, Adrian Boeing
autogenerated on Wed Mar 2 2022 01:08:11