Public Member Functions | Static Public Member Functions | Protected Member Functions | Protected Attributes
CDxlCom Class Reference

Generic base class for CDxlGeneric and CDxlGroup. More...

#include <CDxlCom.h>

Inheritance diagram for CDxlCom:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 CDxlCom ()
int getLastError ()
int initPacketHandler ()
bool isInitialized ()
int setPacketHandler (CDxlPacketHandler *packetHandler)
 Set packet handler to something else than direct serial port.

Static Public Member Functions

static const char * translateErrorCode (int errorCode)

Protected Member Functions

int receivePacketWait (CDxlStatusPacket *packet, int seconds=DXL_PKT_RECV_WAIT_TIME_SEC, int microseconds=DXL_PKT_RECV_WAIT_TIME_USEC)
 Packet commands. Synchronous (blocking) interface.
int sendPacket (CDxlPacket *packet, bool replyExpected=true)
 Packet commands. Synchronous (blocking) interface.

Protected Attributes

bool mInitialized
int mLastError
CLog2 mLog
CDxlPacketHandlermPacketHandler
LxSerialmSerialPort

Detailed Description

Generic base class for CDxlGeneric and CDxlGroup.

Both single dynamixels/3mxls and groups of dynamixels/3mxls have to send packets, use the serial port and do proper error handling.

Definition at line 92 of file CDxlCom.h.


Constructor & Destructor Documentation

Definition at line 13 of file CDxlCom.cpp.


Member Function Documentation

int CDxlCom::getLastError ( ) [inline]

Definition at line 123 of file CDxlCom.h.

Definition at line 34 of file CDxlCom.cpp.

bool CDxlCom::isInitialized ( ) [inline]

Definition at line 112 of file CDxlCom.h.

int CDxlCom::receivePacketWait ( CDxlStatusPacket packet,
int  seconds = DXL_PKT_RECV_WAIT_TIME_SEC,
int  microseconds = DXL_PKT_RECV_WAIT_TIME_USEC 
) [protected]

Packet commands. Synchronous (blocking) interface.

Definition at line 116 of file CDxlCom.cpp.

int CDxlCom::sendPacket ( CDxlPacket packet,
bool  replyExpected = true 
) [protected]

Packet commands. Synchronous (blocking) interface.

Definition at line 80 of file CDxlCom.cpp.

int CDxlCom::setPacketHandler ( CDxlPacketHandler packetHandler)

Set packet handler to something else than direct serial port.

Becomes owner

Definition at line 23 of file CDxlCom.cpp.

const char * CDxlCom::translateErrorCode ( int  errorCode) [static]
Returns:
Human-readable error code

Reimplemented in C3mxl.

Definition at line 42 of file CDxlCom.cpp.


Member Data Documentation

bool CDxlCom::mInitialized [protected]

Definition at line 96 of file CDxlCom.h.

int CDxlCom::mLastError [protected]

Definition at line 97 of file CDxlCom.h.

CLog2 CDxlCom::mLog [protected]

Reimplemented in C3mxl, CDxlGeneric, CDynamixel, and CDxlGroup.

Definition at line 95 of file CDxlCom.h.

Definition at line 100 of file CDxlCom.h.

Definition at line 99 of file CDxlCom.h.


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


threemxl
Author(s):
autogenerated on Fri Aug 28 2015 13:21:08