Skip to content
Snippets Groups Projects
port_handler_linux.c 8.61 KiB
Newer Older
leon's avatar
leon committed
/*******************************************************************************
* Copyright (c) 2016, ROBOTIS CO., LTD.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* * Redistributions of source code must retain the above copyright notice, this
*   list of conditions and the following disclaimer.
*
* * Redistributions in binary form must reproduce the above copyright notice,
*   this list of conditions and the following disclaimer in the documentation
*   and/or other materials provided with the distribution.
*
* * Neither the name of ROBOTIS nor the names of its
*   contributors may be used to endorse or promote products derived from
*   this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*******************************************************************************/

leon's avatar
leon committed
/* Author: Ryu Woon Jung (Leon) */
leon's avatar
leon committed

leon's avatar
leon committed
#include <stdio.h>
#include <fcntl.h>
#include <string.h>
#include <stdlib.h>
#include <unistd.h>
#include <termios.h>
#include <time.h>
#include <sys/time.h>
#include <sys/ioctl.h>
#include <linux/serial.h>

#include "dynamixel_sdk_linux/port_handler_linux.h"
leon's avatar
leon committed

#define LATENCY_TIMER   8  // msec (USB latency timer) [was changed from 4 due to the Ubuntu update 16.04.2]
leon's avatar
leon committed

typedef struct
{
leon's avatar
leon committed
  int     socket_fd;
  int     baudrate;
  char    port_name[30];
leon's avatar
leon committed

leon's avatar
leon committed
  double  packet_start_time;
  double  packet_timeout;
leon's avatar
leon committed
  double  tx_time_per_byte;
leon's avatar
leon committed
}PortData;
leon's avatar
leon committed

leon's avatar
leon committed
static PortData *portData;
leon's avatar
leon committed

int portHandlerLinux(const char *port_name)
leon's avatar
leon committed
{
leon's avatar
leon committed
  int port_num;
leon's avatar
leon committed

leon's avatar
leon committed
  if (portData == NULL)
leon's avatar
leon committed
  {
leon's avatar
leon committed
    port_num = 0;
    g_used_port_num = 1;
    portData = (PortData *)calloc(1, sizeof(PortData));
    g_is_using = (uint8_t*)calloc(1, sizeof(uint8_t));
leon's avatar
leon committed
  }
  else
  {
leon's avatar
leon committed
    for (port_num = 0; port_num < g_used_port_num; port_num++)
leon's avatar
leon committed
    {
leon's avatar
leon committed
      if (!strcmp(portData[port_num].port_name, port_name))
leon's avatar
leon committed
        break;
    }
leon's avatar
leon committed

leon's avatar
leon committed
    if (port_num == g_used_port_num)
leon's avatar
leon committed
    {
leon's avatar
leon committed
      for (port_num = 0; port_num < g_used_port_num; port_num++)
leon's avatar
leon committed
      {
leon's avatar
leon committed
        if (portData[port_num].socket_fd != -1)
leon's avatar
leon committed
          break;
      }

leon's avatar
leon committed
      if (port_num == g_used_port_num)
leon's avatar
leon committed
      {
leon's avatar
leon committed
        g_used_port_num++;
        portData = (PortData*)realloc(portData, g_used_port_num * sizeof(PortData));
        g_is_using = (uint8_t*)realloc(g_is_using, g_used_port_num * sizeof(uint8_t));
leon's avatar
leon committed
      }
leon's avatar
leon committed
    }
    else
    {
leon's avatar
leon committed
      printf("[PortHandler setup] The port number %d has same device name... reinitialize port number %d!!\n", port_num, port_num);
leon's avatar
leon committed
    }
leon's avatar
leon committed
  }
leon's avatar
leon committed

leon's avatar
leon committed
  portData[port_num].socket_fd = -1;
  portData[port_num].baudrate = DEFAULT_BAUDRATE;
  portData[port_num].packet_start_time = 0.0;
  portData[port_num].packet_timeout = 0.0;
  portData[port_num].tx_time_per_byte = 0.0;
leon's avatar
leon committed

leon's avatar
leon committed

leon's avatar
leon committed
  setPortNameLinux(port_num, port_name);
leon's avatar
leon committed

leon's avatar
leon committed
  return port_num;
leon's avatar
leon committed
}

leon's avatar
leon committed
uint8_t openPortLinux(int port_num)
leon's avatar
leon committed
{
leon's avatar
leon committed
  return setBaudRateLinux(port_num, portData[port_num].baudrate);
leon's avatar
leon committed
}

void closePortLinux(int port_num)
leon's avatar
leon committed
{
leon's avatar
leon committed
  if (portData[port_num].socket_fd != -1)
leon's avatar
leon committed
  {
leon's avatar
leon committed
    close(portData[port_num].socket_fd);
    portData[port_num].socket_fd = -1;
leon's avatar
leon committed
  }
leon's avatar
leon committed
}

void clearPortLinux(int port_num)
leon's avatar
leon committed
{
leon's avatar
leon committed
  tcflush(portData[port_num].socket_fd, TCIOFLUSH);
leon's avatar
leon committed
}

void setPortNameLinux(int port_num, const char *port_name)
leon's avatar
leon committed
{
leon's avatar
leon committed
  strcpy(portData[port_num].port_name, port_name);
leon's avatar
leon committed
}

char *getPortNameLinux(int port_num)
leon's avatar
leon committed
{
leon's avatar
leon committed
  return portData[port_num].port_name;
leon's avatar
leon committed
}

leon's avatar
leon committed
uint8_t setBaudRateLinux(int port_num, const int baudrate)
leon's avatar
leon committed
{
leon's avatar
leon committed
  int baud = getCFlagBaud(baudrate);
leon's avatar
leon committed

  closePortLinux(port_num);

leon's avatar
leon committed
  if (baud <= 0)   // custom baudrate
leon's avatar
leon committed
  {
    setupPortLinux(port_num, B38400);
leon's avatar
leon committed
    portData[port_num].baudrate = baudrate;
leon's avatar
leon committed
    return setCustomBaudrateLinux(port_num, baudrate);
  }
  else
  {
leon's avatar
leon committed
    portData[port_num].baudrate = baudrate;
    return setupPortLinux(port_num, baud);
leon's avatar
leon committed
  }
leon's avatar
leon committed
}

int getBaudRateLinux(int port_num)
leon's avatar
leon committed
{
leon's avatar
leon committed
  return portData[port_num].baudrate;
leon's avatar
leon committed
}

int getBytesAvailableLinux(int port_num)
leon's avatar
leon committed
{
leon's avatar
leon committed
  int bytes_available;
  ioctl(portData[port_num].socket_fd, FIONREAD, &bytes_available);
  return bytes_available;
leon's avatar
leon committed
}

int readPortLinux(int port_num, uint8_t *packet, int length)
leon's avatar
leon committed
{
leon's avatar
leon committed
  return read(portData[port_num].socket_fd, packet, length);
leon's avatar
leon committed
}

int writePortLinux(int port_num, uint8_t *packet, int length)
leon's avatar
leon committed
{
leon's avatar
leon committed
  return write(portData[port_num].socket_fd, packet, length);
leon's avatar
leon committed
}

void setPacketTimeoutLinux(int port_num, uint16_t packet_length)
leon's avatar
leon committed
{
leon's avatar
leon committed
  portData[port_num].packet_start_time = getCurrentTimeLinux();
  portData[port_num].packet_timeout = (portData[port_num].tx_time_per_byte * (double)packet_length) + (LATENCY_TIMER * 2.0) + 2.0;
leon's avatar
leon committed
}

void setPacketTimeoutMSecLinux(int port_num, double msec)
leon's avatar
leon committed
{
leon's avatar
leon committed
  portData[port_num].packet_start_time = getCurrentTimeLinux();
  portData[port_num].packet_timeout = msec;
leon's avatar
leon committed
}

leon's avatar
leon committed
uint8_t isPacketTimeoutLinux(int port_num)
leon's avatar
leon committed
{
leon's avatar
leon committed
  if (getTimeSinceStartLinux(port_num) > portData[port_num].packet_timeout)
leon's avatar
leon committed
  {
leon's avatar
leon committed
    portData[port_num].packet_timeout = 0;
leon's avatar
leon committed
  }
leon's avatar
leon committed
}

double getCurrentTimeLinux()
leon's avatar
leon committed
{
leon's avatar
leon committed
  struct timespec tv;
  clock_gettime(CLOCK_REALTIME, &tv);
  return ((double)tv.tv_sec*1000.0 + (double)tv.tv_nsec*0.001*0.001);
leon's avatar
leon committed
}

double getTimeSinceStartLinux(int port_num)
leon's avatar
leon committed
{
leon's avatar
leon committed
  double time_since_start;
leon's avatar
leon committed

leon's avatar
leon committed
  time_since_start = getCurrentTimeLinux() - portData[port_num].packet_start_time;
  if (time_since_start < 0.0)
    portData[port_num].packet_start_time = getCurrentTimeLinux();
leon's avatar
leon committed

leon's avatar
leon committed
  return time_since_start;
leon's avatar
leon committed
}

leon's avatar
leon committed
uint8_t setupPortLinux(int port_num, int cflag_baud)
leon's avatar
leon committed
{
leon's avatar
leon committed
  struct termios newtio;
leon's avatar
leon committed

leon's avatar
leon committed
  portData[port_num].socket_fd = open(portData[port_num].port_name, O_RDWR | O_NOCTTY | O_NONBLOCK);
leon's avatar
leon committed

leon's avatar
leon committed
  if (portData[port_num].socket_fd < 0)
leon's avatar
leon committed
  {
    printf("[PortHandlerLinux::SetupPort] Error opening serial port!\n");
leon's avatar
leon committed
  }
leon's avatar
leon committed

leon's avatar
leon committed
  bzero(&newtio, sizeof(newtio)); // clear struct for new port settings
leon's avatar
leon committed

leon's avatar
leon committed
  newtio.c_cflag = cflag_baud | CS8 | CLOCAL | CREAD;
  newtio.c_iflag = IGNPAR;
  newtio.c_oflag = 0;
  newtio.c_lflag = 0;
  newtio.c_cc[VTIME] = 0;
  newtio.c_cc[VMIN] = 0;
leon's avatar
leon committed

leon's avatar
leon committed
  // clean the buffer and activate the settings for the port
leon's avatar
leon committed
  tcflush(portData[port_num].socket_fd, TCIFLUSH);
  tcsetattr(portData[port_num].socket_fd, TCSANOW, &newtio);
leon's avatar
leon committed

leon's avatar
leon committed
  portData[port_num].tx_time_per_byte = (1000.0 / (double)portData[port_num].baudrate) * 10.0;
leon's avatar
leon committed
}

leon's avatar
leon committed
uint8_t setCustomBaudrateLinux(int port_num, int speed)
leon's avatar
leon committed
{
leon's avatar
leon committed
  // try to set a custom divisor
  struct serial_struct ss;
leon's avatar
leon committed
  if (ioctl(portData[port_num].socket_fd, TIOCGSERIAL, &ss) != 0)
leon's avatar
leon committed
  {
    printf("[PortHandlerLinux::SetCustomBaudrate] TIOCGSERIAL failed!\n");
leon's avatar
leon committed
  }
leon's avatar
leon committed

leon's avatar
leon committed
  ss.flags = (ss.flags & ~ASYNC_SPD_MASK) | ASYNC_SPD_CUST;
  ss.custom_divisor = (ss.baud_base + (speed / 2)) / speed;
  int closest_speed = ss.baud_base / ss.custom_divisor;
leon's avatar
leon committed

leon's avatar
leon committed
  if (closest_speed < speed * 98 / 100 || closest_speed > speed * 102 / 100)
  {
    printf("[PortHandlerLinux::setCustomBaudrate] Cannot set speed to %d, closest is %d \n", speed, closest_speed);
leon's avatar
leon committed
  }
leon's avatar
leon committed

leon's avatar
leon committed
  if (ioctl(portData[port_num].socket_fd, TIOCSSERIAL, &ss) < 0)
leon's avatar
leon committed
  {
    printf("[PortHandlerLinux::setCustomBaudrate] TIOCSSERIAL failed!\n");
leon's avatar
leon committed
  }
leon's avatar
leon committed

leon's avatar
leon committed
  portData[port_num].tx_time_per_byte = (1000.0 / (double)speed) * 10.0;
leon's avatar
leon committed
}

int getCFlagBaud(int baudrate)
leon's avatar
leon committed
{
leon's avatar
leon committed
  switch (baudrate)
  {
leon's avatar
leon committed
    case 9600:
leon's avatar
leon committed
      return B9600;
leon's avatar
leon committed
    case 19200:
leon's avatar
leon committed
      return B19200;
leon's avatar
leon committed
    case 38400:
leon's avatar
leon committed
      return B38400;
leon's avatar
leon committed
    case 57600:
leon's avatar
leon committed
      return B57600;
leon's avatar
leon committed
    case 115200:
leon's avatar
leon committed
      return B115200;
leon's avatar
leon committed
    case 230400:
leon's avatar
leon committed
      return B230400;
leon's avatar
leon committed
    case 460800:
leon's avatar
leon committed
      return B460800;
leon's avatar
leon committed
    case 500000:
leon's avatar
leon committed
      return B500000;
leon's avatar
leon committed
    case 576000:
leon's avatar
leon committed
      return B576000;
leon's avatar
leon committed
    case 921600:
leon's avatar
leon committed
      return B921600;
leon's avatar
leon committed
    case 1000000:
leon's avatar
leon committed
      return B1000000;
leon's avatar
leon committed
    case 1152000:
leon's avatar
leon committed
      return B1152000;
leon's avatar
leon committed
    case 1500000:
leon's avatar
leon committed
      return B1500000;
leon's avatar
leon committed
    case 2000000:
leon's avatar
leon committed
      return B2000000;
leon's avatar
leon committed
    case 2500000:
leon's avatar
leon committed
      return B2500000;
leon's avatar
leon committed
    case 3000000:
leon's avatar
leon committed
      return B3000000;
leon's avatar
leon committed
    case 3500000:
leon's avatar
leon committed
      return B3500000;
leon's avatar
leon committed
    case 4000000:
leon's avatar
leon committed
      return B4000000;
leon's avatar
leon committed
    default:
leon's avatar
leon committed
      return -1;
  }
leon's avatar
leon committed
}