The class for control port in Arduino.
More...
#include <port_handler_arduino.h>
|
void | clearPort () |
| The function that clears the port The function clears the port. More...
|
|
void | closePort () |
| The function that closes the port The function closes the port. More...
|
|
int | getBaudRate () |
| The function that returns current baudrate set into the port handler The function returns current baudrate set into the port handler. More...
|
|
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. More...
|
|
char * | getPortName () |
| The function that returns port name set into the port handler The function returns current port name set into the port handler. More...
|
|
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(). More...
|
|
bool | openPort () |
| The function that opens the port The function calls PortHandlerArduino::setBaudRate() to open the port. More...
|
|
| 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. More...
|
|
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. More...
|
|
bool | setBaudRate (const int baudrate) |
| The function that sets baudrate into the port handler The function sets baudrate into the port handler. More...
|
|
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. More...
|
|
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. More...
|
|
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. More...
|
|
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. More...
|
|
virtual | ~PortHandlerArduino () |
| The function that closes the port The function calls PortHandlerArduino::closePort() to close the port. More...
|
|
Public Member Functions inherited from dynamixel::PortHandler |
virtual | ~PortHandler () |
|
The class for control port in Arduino.
Definition at line 37 of file port_handler_arduino.h.
dynamixel::PortHandlerArduino::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.
virtual dynamixel::PortHandlerArduino::~PortHandlerArduino |
( |
| ) |
|
|
inlinevirtual |
int dynamixel::PortHandlerArduino::checkBaudrateAvailable |
( |
int |
baudrate | ) |
|
|
private |
void dynamixel::PortHandlerArduino::clearPort |
( |
| ) |
|
|
virtual |
void dynamixel::PortHandlerArduino::closePort |
( |
| ) |
|
|
virtual |
int dynamixel::PortHandlerArduino::getBaudRate |
( |
| ) |
|
|
virtual |
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.
int dynamixel::PortHandlerArduino::getBytesAvailable |
( |
| ) |
|
|
virtual |
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.
double dynamixel::PortHandlerArduino::getCurrentTime |
( |
| ) |
|
|
private |
char* dynamixel::PortHandlerArduino::getPortName |
( |
| ) |
|
|
virtual |
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.
double dynamixel::PortHandlerArduino::getTimeSinceStart |
( |
| ) |
|
|
private |
bool dynamixel::PortHandlerArduino::isPacketTimeout |
( |
| ) |
|
|
virtual |
bool dynamixel::PortHandlerArduino::openPort |
( |
| ) |
|
|
virtual |
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
-
packet | Buffer for the packet received |
length | Length 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
-
- 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_length | Length 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_length | Length 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
-
Implements dynamixel::PortHandler.
void dynamixel::PortHandlerArduino::setPowerOff |
( |
| ) |
|
|
private |
void dynamixel::PortHandlerArduino::setPowerOn |
( |
| ) |
|
|
private |
void dynamixel::PortHandlerArduino::setTxDisable |
( |
| ) |
|
|
private |
void dynamixel::PortHandlerArduino::setTxEnable |
( |
| ) |
|
|
private |
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
-
packet | Buffer which would be written on the port buffer |
length | Length of the buffer for write |
- Returns
- -1
-
when error was occurred
-
or Length of bytes written
Implements dynamixel::PortHandler.
int dynamixel::PortHandlerArduino::baudrate_ |
|
private |
double dynamixel::PortHandlerArduino::packet_start_time_ |
|
private |
double dynamixel::PortHandlerArduino::packet_timeout_ |
|
private |
char dynamixel::PortHandlerArduino::port_name_[100] |
|
private |
int dynamixel::PortHandlerArduino::socket_fd_ |
|
private |
double dynamixel::PortHandlerArduino::tx_time_per_byte |
|
private |
The documentation for this class was generated from the following file: