Public Member Functions | Private Member Functions | Private Attributes
dynamixel::PortHandlerArduino Class Reference

The class for control port in Arduino. More...

#include <port_handler_arduino.h>

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

List of all members.

Public Member Functions

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

Private Member Functions

int checkBaudrateAvailable (int baudrate)
double getCurrentTime ()
double getTimeSinceStart ()
void setPowerOff ()
void setPowerOn ()
void setTxDisable ()
void setTxEnable ()
bool setupPort (const int cflag_baud)

Private Attributes

int baudrate_
double packet_start_time_
double packet_timeout_
char port_name_ [100]
int socket_fd_
double tx_time_per_byte

Detailed Description

The class for control port in Arduino.

Definition at line 37 of file port_handler_arduino.h.


Constructor & Destructor Documentation

The function that initializes instance of PortHandler and gets port_name The function initializes instance of PortHandler and gets port_name.

The function that closes the port The function calls PortHandlerArduino::closePort() to close the port.

Definition at line 75 of file port_handler_arduino.h.


Member Function Documentation

The function that clears the port The function clears the port.

Implements dynamixel::PortHandler.

The function that closes the port The function closes the port.

Implements dynamixel::PortHandler.

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

Returns:
Baudrate

Implements dynamixel::PortHandler.

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

Returns:
Length of read-able bytes in the port buffer

Implements dynamixel::PortHandler.

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

Returns:
Port name

Implements dynamixel::PortHandler.

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

Implements dynamixel::PortHandler.

The function that opens the port The function calls PortHandlerArduino::setBaudRate() to open the port.

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

Implements dynamixel::PortHandler.

int dynamixel::PortHandlerArduino::readPort ( uint8_t *  packet,
int  length 
) [virtual]

The function that reads bytes from the port buffer The function gets bytes from the port buffer, 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

Implements dynamixel::PortHandler.

bool dynamixel::PortHandlerArduino::setBaudRate ( const int  baudrate) [virtual]

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

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

Implements dynamixel::PortHandler.

void dynamixel::PortHandlerArduino::setPacketTimeout ( uint16_t  packet_length) [virtual]

The function that sets and starts stopwatch for watching packet timeout 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

Implements dynamixel::PortHandler.

void dynamixel::PortHandlerArduino::setPacketTimeout ( double  msec) [virtual]

The function that sets and starts stopwatch for watching packet timeout 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

Implements dynamixel::PortHandler.

void dynamixel::PortHandlerArduino::setPortName ( const char *  port_name) [virtual]

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

Parameters:
port_namePort name

Implements dynamixel::PortHandler.

bool dynamixel::PortHandlerArduino::setupPort ( const int  cflag_baud) [private]
int dynamixel::PortHandlerArduino::writePort ( uint8_t *  packet,
int  length 
) [virtual]

The function that writes bytes on the port buffer The function writes bytes on the port buffer, 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

Implements dynamixel::PortHandler.


Member Data Documentation

Definition at line 41 of file port_handler_arduino.h.

Definition at line 44 of file port_handler_arduino.h.

Definition at line 45 of file port_handler_arduino.h.

Definition at line 42 of file port_handler_arduino.h.

Definition at line 40 of file port_handler_arduino.h.

Definition at line 46 of file port_handler_arduino.h.


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


ros
Author(s): Pyo , Zerom , Leon
autogenerated on Sat Jun 8 2019 18:32:12