Newer
Older
/*******************************************************************************
* 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.
*******************************************************************************/
#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>
Leon Ryuwoon Jung
committed
#include "port_handler_linux.h"
Leon Ryuwoon Jung
committed
#define LATENCY_TIMER 8 // msec (USB latency timer) [was changed from 4 due to the Ubuntu update 16.04.2]
char port_name[100];
int portHandlerLinux(const char *port_name)
port_num = 0;
g_used_port_num = 1;
portData = (PortData *)calloc(1, sizeof(PortData));
g_is_using = (uint8_t*)calloc(1, sizeof(uint8_t));
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));
printf("[PortHandler setup] The port number %d has same device name... reinitialize port number %d!!\n", port_num, port_num);
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;
g_is_using[port_num] = False;
close(portData[port_num].socket_fd);
portData[port_num].socket_fd = -1;
void setPortNameLinux(int port_num, const char *port_name)
char *getPortNameLinux(int port_num)
return setCustomBaudrateLinux(port_num, baudrate);
}
else
{
portData[port_num].baudrate = baudrate;
return setupPortLinux(port_num, baud);
int getBytesAvailableLinux(int port_num)
int bytes_available;
ioctl(portData[port_num].socket_fd, FIONREAD, &bytes_available);
return bytes_available;
int readPortLinux(int port_num, uint8_t *packet, int length)
int writePortLinux(int port_num, uint8_t *packet, int length)
void setPacketTimeoutLinux(int port_num, uint16_t packet_length)
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;
void setPacketTimeoutMSecLinux(int port_num, double msec)
portData[port_num].packet_start_time = getCurrentTimeLinux();
portData[port_num].packet_timeout = msec;
if (getTimeSinceStartLinux(port_num) > portData[port_num].packet_timeout)
return True;
return False;
struct timespec tv;
clock_gettime(CLOCK_REALTIME, &tv);
return ((double)tv.tv_sec*1000.0 + (double)tv.tv_nsec*0.001*0.001);
double getTimeSinceStartLinux(int port_num)
time_since_start = getCurrentTimeLinux() - portData[port_num].packet_start_time;
if (time_since_start < 0.0)
portData[port_num].packet_start_time = getCurrentTimeLinux();
portData[port_num].socket_fd = open(portData[port_num].port_name, O_RDWR | O_NOCTTY | O_NONBLOCK);
{
printf("[PortHandlerLinux::SetupPort] Error opening serial port!\n");
return False;
bzero(&newtio, sizeof(newtio)); // clear struct for new port settings
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;
tcflush(portData[port_num].socket_fd, TCIFLUSH);
tcsetattr(portData[port_num].socket_fd, TCSANOW, &newtio);
portData[port_num].tx_time_per_byte = (1000.0 / (double)portData[port_num].baudrate) * 10.0;
return True;
{
printf("[PortHandlerLinux::SetCustomBaudrate] TIOCGSERIAL failed!\n");
return False;
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;
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);
return False;
{
printf("[PortHandlerLinux::setCustomBaudrate] TIOCSSERIAL failed!\n");
return False;
portData[port_num].tx_time_per_byte = (1000.0 / (double)speed) * 10.0;
return True;