Public Member Functions | Static Public Member Functions | Public Attributes | Static Public Attributes | List of all members
dynamixel::PortHandler Class Referenceabstract

The class for port control that inherits PortHandlerLinux, PortHandlerWindows, PortHandlerMac, or PortHandlerArduino. More...

#include <port_handler.h>

Inheritance diagram for dynamixel::PortHandler:
Inheritance graph
[legend]

Public Member Functions

virtual void clearPort ()=0
 The function that clears the port @description The function clears the port. More...
 
virtual void closePort ()=0
 The function that closes the port @description The function closes the port. More...
 
virtual int getBaudRate ()=0
 The function that returns current baudrate set into the port handler @description The function returns current baudrate set into the port handler. More...
 
virtual int getBytesAvailable ()=0
 The function that checks how much bytes are able to be read from the port buffer @description The function checks how much bytes are able to be read from the port buffer @description and returns the number. More...
 
virtual char * getPortName ()=0
 The function that returns port name set into the port handler @description The function returns current port name set into the port handler. More...
 
virtual bool isPacketTimeout ()=0
 The function that checks whether packet timeout is occurred @description The function checks whether current time is passed by the time of packet timeout from the time set by PortHandlerLinux::setPacketTimeout(). More...
 
virtual bool openPort ()=0
 The function that opens the port @description The function calls PortHandlerLinux::setBaudRate() to open the port. More...
 
virtual int readPort (uint8_t *packet, int length)=0
 The function that reads bytes from the port buffer @description The function gets bytes from the port buffer, @description and returns a number of bytes read. More...
 
virtual bool setBaudRate (const int baudrate)=0
 The function that sets baudrate into the port handler @description The function sets baudrate into the port handler. More...
 
virtual void setPacketTimeout (double msec)=0
 The function that sets and starts stopwatch for watching packet timeout @description The function sets the stopwatch by getting current time and the time of packet timeout with msec. More...
 
virtual void setPacketTimeout (uint16_t packet_length)=0
 The function that sets and starts stopwatch for watching packet timeout @description The function sets the stopwatch by getting current time and the time of packet timeout with packet_length. More...
 
virtual void setPortName (const char *port_name)=0
 The function that sets port name into the port handler @description The function sets port name into the port handler. More...
 
virtual int writePort (uint8_t *packet, int length)=0
 The function that writes bytes on the port buffer @description The function writes bytes on the port buffer, @description and returns a number of bytes which are successfully written. More...
 
virtual ~PortHandler ()
 

Static Public Member Functions

static PortHandlergetPortHandler (const char *port_name)
 The function that gets PortHandler class inheritance @description The function gets class inheritance (PortHandlerLinux / PortHandlerWindows / PortHandlerMac / PortHandlerArduino. More...
 

Public Attributes

bool is_using_
 shows whether the port is in use More...
 

Static Public Attributes

static const int DEFAULT_BAUDRATE_ = 57600
 Default Baudrate. More...
 

Detailed Description

The class for port control that inherits PortHandlerLinux, PortHandlerWindows, PortHandlerMac, or PortHandlerArduino.

Definition at line 56 of file port_handler.h.

Constructor & Destructor Documentation

◆ ~PortHandler()

virtual dynamixel::PortHandler::~PortHandler ( )
inlinevirtual

Definition at line 69 of file port_handler.h.

Member Function Documentation

◆ clearPort()

virtual void dynamixel::PortHandler::clearPort ( )
pure virtual

The function that clears the port @description The function clears the port.

Implemented in dynamixel::PortHandlerArduino, dynamixel::PortHandlerWindows, dynamixel::PortHandlerLinux, and dynamixel::PortHandlerMac.

◆ closePort()

virtual void dynamixel::PortHandler::closePort ( )
pure virtual

The function that closes the port @description The function closes the port.

Implemented in dynamixel::PortHandlerArduino, dynamixel::PortHandlerWindows, dynamixel::PortHandlerLinux, and dynamixel::PortHandlerMac.

◆ getBaudRate()

virtual int dynamixel::PortHandler::getBaudRate ( )
pure virtual

The function that returns current baudrate set into the port handler @description The function returns current baudrate set into the port handler.

Returns
Baudrate

Implemented in dynamixel::PortHandlerArduino, dynamixel::PortHandlerMac, dynamixel::PortHandlerWindows, and dynamixel::PortHandlerLinux.

◆ getBytesAvailable()

virtual int dynamixel::PortHandler::getBytesAvailable ( )
pure virtual

The function that checks how much bytes are able to be read from the port buffer @description The function checks how much bytes are able to be read from the port buffer @description and returns the number.

Returns
Length of read-able bytes in the port buffer

Implemented in dynamixel::PortHandlerArduino, dynamixel::PortHandlerMac, dynamixel::PortHandlerWindows, and dynamixel::PortHandlerLinux.

◆ getPortHandler()

PortHandler * PortHandler::getPortHandler ( const char *  port_name)
static

The function that gets PortHandler class inheritance @description The function gets class inheritance (PortHandlerLinux / PortHandlerWindows / PortHandlerMac / PortHandlerArduino.

Definition at line 36 of file port_handler.cpp.

◆ getPortName()

virtual char* dynamixel::PortHandler::getPortName ( )
pure virtual

The function that returns port name set into the port handler @description The function returns current port name set into the port handler.

Returns
Port name

Implemented in dynamixel::PortHandlerArduino, dynamixel::PortHandlerWindows, dynamixel::PortHandlerLinux, and dynamixel::PortHandlerMac.

◆ isPacketTimeout()

virtual bool dynamixel::PortHandler::isPacketTimeout ( )
pure virtual

The function that checks whether packet timeout is occurred @description The function checks whether current time is passed by the time of packet timeout from the time set by PortHandlerLinux::setPacketTimeout().

Implemented in dynamixel::PortHandlerArduino, dynamixel::PortHandlerMac, dynamixel::PortHandlerWindows, and dynamixel::PortHandlerLinux.

◆ openPort()

virtual bool dynamixel::PortHandler::openPort ( )
pure virtual

The function that opens the port @description The function calls PortHandlerLinux::setBaudRate() to open the port.

Returns
communication results which come from PortHandlerLinux::setBaudRate()

Implemented in dynamixel::PortHandlerArduino, dynamixel::PortHandlerWindows, dynamixel::PortHandlerLinux, and dynamixel::PortHandlerMac.

◆ readPort()

virtual int dynamixel::PortHandler::readPort ( uint8_t *  packet,
int  length 
)
pure virtual

The function that reads bytes from the port buffer @description The function gets bytes from the port buffer, @description and returns a number of bytes read.

Parameters
packetBuffer for the packet received
lengthLength of the buffer for read
Returns
-1
when error was occurred
or Length of bytes read

Implemented in dynamixel::PortHandlerArduino, dynamixel::PortHandlerMac, dynamixel::PortHandlerWindows, and dynamixel::PortHandlerLinux.

◆ setBaudRate()

virtual bool dynamixel::PortHandler::setBaudRate ( const int  baudrate)
pure virtual

The function that sets baudrate into the port handler @description The function sets baudrate into the port handler.

Parameters
baudrateBaudrate
Returns
false
when error was occurred during port opening
or true

Implemented in dynamixel::PortHandlerArduino, dynamixel::PortHandlerWindows, dynamixel::PortHandlerLinux, and dynamixel::PortHandlerMac.

◆ setPacketTimeout() [1/2]

virtual void dynamixel::PortHandler::setPacketTimeout ( double  msec)
pure virtual

The function that sets and starts stopwatch for watching packet timeout @description The function sets the stopwatch by getting current time and the time of packet timeout with msec.

Parameters
packet_lengthLength of the packet expected to be received

Implemented in dynamixel::PortHandlerArduino, dynamixel::PortHandlerMac, dynamixel::PortHandlerWindows, and dynamixel::PortHandlerLinux.

◆ setPacketTimeout() [2/2]

virtual void dynamixel::PortHandler::setPacketTimeout ( uint16_t  packet_length)
pure virtual

The function that sets and starts stopwatch for watching packet timeout @description The function sets the stopwatch by getting current time and the time of packet timeout with packet_length.

Parameters
packet_lengthLength of the packet expected to be received

Implemented in dynamixel::PortHandlerArduino, dynamixel::PortHandlerMac, dynamixel::PortHandlerWindows, and dynamixel::PortHandlerLinux.

◆ setPortName()

virtual void dynamixel::PortHandler::setPortName ( const char *  port_name)
pure virtual

The function that sets port name into the port handler @description The function sets port name into the port handler.

Parameters
port_namePort name

Implemented in dynamixel::PortHandlerArduino, dynamixel::PortHandlerWindows, dynamixel::PortHandlerLinux, and dynamixel::PortHandlerMac.

◆ writePort()

virtual int dynamixel::PortHandler::writePort ( uint8_t *  packet,
int  length 
)
pure virtual

The function that writes bytes on the port buffer @description The function writes bytes on the port buffer, @description and returns a number of bytes which are successfully written.

Parameters
packetBuffer which would be written on the port buffer
lengthLength of the buffer for write
Returns
-1
when error was occurred
or Length of bytes written

Implemented in dynamixel::PortHandlerArduino, dynamixel::PortHandlerMac, dynamixel::PortHandlerWindows, and dynamixel::PortHandlerLinux.

Member Data Documentation

◆ DEFAULT_BAUDRATE_

const int dynamixel::PortHandler::DEFAULT_BAUDRATE_ = 57600
static

Default Baudrate.

Definition at line 59 of file port_handler.h.

◆ is_using_

bool dynamixel::PortHandler::is_using_

shows whether the port is in use

Definition at line 67 of file port_handler.h.


The documentation for this class was generated from the following files:


dynamixel_sdk
Author(s): Gilbert , Zerom , Darby Lim , Leon
autogenerated on Wed Mar 2 2022 00:13:50