Matlab PacketHandler
- Description
Base functions for packet construction.
-
Members
None
-
Methods
Methods | Description |
---|---|
packetHandler | Initializes members of packet data pointer struct |
printTxRxResult | Shows communication result |
printRxPacketError | Shows hardware error |
getLastTxRxResult | Gets last communication result |
getLastRxPacketError | Gets last hardware error |
setDataWrite | Gets last communication result |
getDataRead | Gets last hardware error |
txPacket | Transmits the packet |
rxPacket | Receives the packet |
txRxPacket | Transmits and receives the packet |
ping | ping DYNAMIXEL |
pingGetModelNum | Ping DYNAMIXEL and get its model number |
broadcastPing | ping all connected DYNAMIXEL’s |
getBroadcastPingResult | Get IDs of DYNAMIXEL’s responded by BroadcastPing2 |
action | Commands ‘Run’ the Regwritten |
regWrite | Writes the packets and wait for the ‘Action’ command |
reboot | Reboots DYNAMIXEL |
factoryReset | Resets all DYNAMIXEL settings |
readTx | Transmits N byte read instruction packet |
readRx | Receives N byte read status packet |
readTxRx | Transmits and receives N byte packet |
read1ByteTx | Transmits 1 byte read instruction packet |
read1ByteRx | Receives 1 byte read status packet |
read1ByteTxRx | Transmits and receives 1 byte packet |
read2ByteTx | Transmits 2 byte read instruction packet |
read2ByteRx | Receives 2 byte read status packet |
read2ByteTxRx | Transmits and receives 2 byte packet |
read4ByteTx | Transmits 4 byte read instruction packet |
read4ByteRx | Receives 4 byte read status packet |
read4ByteTxRx | Transmits and receives 4 byte packet |
writeTxOnly | Transmits N byte write instruction packet |
writeTxRx | Transmits and receives N byte packet |
write1ByteTxOnly | Transmits 1 byte write instruction packet |
write1ByteTxRx | Transmits and receives 1 byte packet |
write2ByteTxOnly | Transmits 2 byte write instruction packet |
write2ByteTxRx | Transmits and receives 2 byte packet |
write4ByteTxOnly | Transmits 4 byte write instruction packet |
write4ByteTxRx | Transmits and receives 4 byte packet |
regWriteTxOnly | Transmits register write instruction packet |
regWriteTxRx | Transmits and receives register write packet |
syncReadTx | Transmits N byte sync read Instruction packet |
syncWriteTxOnly | Transmits N byte sync write Instruction packet |
bulkReadTx | Transmits N byte bulk read Instruction packet |
bulkWriteTxOnly | Transmits N byte bulk write Instruction packet |
- Enumerator
Enumerator | Description |
---|---|
DXL_MAKEWORD(a, b) | makes value from a and b to word type |
DXL_MAKEDWORD(a, b) | makes value from a and b to dword type |
DXL_LOWORD(l) | gets lower word type value from l |
DXL_HIWORD(l) | gets higher word type value from l |
DXL_LOBYTE(w) | gets lower byte type value from w |
DXL_HIBYTE(w) | gets higher byte type value from w |
BROADCAST_ID | := 0xFE Broadcast ID |
MAX_ID | := 0xFC Maximum ID value |
INST_PING | := 1 Instruction value of ping |
INST_READ | := 2 Instruction value of Read |
INST_WRITE | := 3 Instruction value of Write |
INST_REG_WRITE | := 4 Instruction value of Register Write |
INST_ACTION | := 5 Instruction value of Action |
INST_FACTORY_RESET | := 6 Instruction value of Factory Reset |
INST_SYNC_WRITE | := 131 Instruction value of Sync Write |
INST_BULK_READ | := 146 Instruction value of Bulk Read |
INST_REBOOT | := 8 Instruction value of Reboot |
INST_STATUS | := 85 Instruction value of Status |
INST_SYNC_READ | := 130 Instruction value of Sync Read |
INST_BULK_WRITE | := 147 Instruction value of Bulk Write |
COMM_SUCCESS | := 0 Status of Communication Success |
COMM_PORT_BUSY | := -1000 Status of Port in use |
COMM_TX_FAIL | := -1001 Status of Transmit packet failed |
COMM_RX_FAIL | := -1002 Status of Receive packet failed |
COMM_TX_ERROR | := -2000 Status of Transmit packet error |
COMM_RX_WAITING | := -3000 Status of Receive packet waiting |
COMM_RX_TIMEOUT | := -3001 Status of Receive packet timeout |
COMM_RX_CORRUPT | := -3002 Status of Receive packet corrupt |
COMM_NOT_AVAILABLE | := -9000 Status of Unavailable in protocol 1.0 |
Method References
packetHandler
- Syntax
void packetHandler()
-
Parameters
None
-
Detailed Description
This function initializes the parameters for packet construction. The function resizes
packetData
struct and initialzes struct members.
printTxRxResult
- Syntax
void printTxRxResult(int protocol_version, int result)
- Parameters
Parameters | Description |
---|---|
protocol_version | Protocol version |
result | Communication result |
-
Detailed Description
This function calls either
printTxRxResult1
orprintTxRxResult2
function depending on theprotocol_version
. The function prints out on the console window what communicationresult
value means.
printRxPacketError
- Syntax
void printRxPacketError(int protocol_version, int error)
- Parameters
Parameters | Description |
---|---|
protocol_version | Protocol version |
error | Hardware error |
-
Detailed Description
This function calls either
printRxPacketError1
orprintRxPacketError2
function depending on theprotocol_version
. The function prints out on the console window what hardwareerror
value means.
getLastTxRxResult
- Syntax
int getLastTxRxResult(int port_num, int protocol_version)
- Parameters
Parameters | Description |
---|---|
port_num | Port number |
protocol_version | Protocol version |
-
Detailed Description
This function calls either
getLastTxRxResult1
orgetLastTxRxResult2
function depending on theprotocol_version
. The function returns the communication result of #port_num
port.
getLastRxPacketError
- Syntax
byte getLastRxPacketError(int port_num, int protocol_version)
- Parameters
Parameters | Description |
---|---|
port_num | Port number |
protocol_version | Protocol version |
-
Detailed Description
This function calls either
getLastRxPacketError1
orgetLastRxPacketError2
function depending on theprotocol_version
. The function returns the hardware error of #port_num
port.
setDataWrite
- Syntax
void setDataWrite(int port_num, int protocol_version, int data_length, int data_pos, int data)
- Parameters
Parameters | Description |
---|---|
port_num | Port number |
protocol_version | Protocol version |
data_length | Data length |
data_pos | Targeted position of array element |
data | Data |
-
Detailed Description
This function calls either
setDataWrite1
orsetDataWrite2
function depending on theprotocol_version
. The function putsData length
bytes ofData
intodata_pos
element of array for writing data at #port_num
port tx buffer.
getDataRead
- Syntax
int getDataRead(int port_num, int protocol_version, int data_length, int data_pos)
- Parameters
Parameters | Description |
---|---|
port_num | Port number |
protocol_version | Protocol version |
data_length | Data length |
data_pos | Targeted position of array element |
-
Detailed Description
This function calls either
getDataRead1
orgetDataRead2
function depending on theprotocol_version
. The function getsdata_length
bytes of the data located indata_pos
position of read data array that from #port_num
port rx buffer.
txPacket
- Syntax
void txPacket(int port_num, int protocol_version)
- Parameters
Parameters | Description |
---|---|
port_num | Port_num |
protocol_version | Protocol version |
-
Detailed Description
This function calls either
txPacket1
ortxPacket2
function depending on theprotocol_version
. The function transmits the packet. The function clears the port byclearPort
function at first, and stores data in the txpacket storage of #port_num
port. The communication result and the hardware error are available when the function is terminated.
rxPacket
- Syntax
void rxPacket(int port_num, int protocol_version)
- Parameters
Parameters | Description |
---|---|
port_num | Port number |
protocol_version | Protocol version |
-
Detailed Description
This function calls either
rxPacket1
orrxPacket2
function depending on theprotocol_version
. The function repeatedly tries to receive packets from #port_num
port rx buffer until whole packets that it waits to get have arrived, or the packet wait time limit is over, while it filters garbage signals and verify correctness of received signal. The communication result and the hardware error are available when the function is terminated.
txRxPacket
- Syntax ```c void txRxPacket(int port_num, int protocol_version)
- Parameters
| Parameters | Description |
|:-----------------|:-----------------|
| port_num | Port number |
| protocol_version | Protocol version |
- Detailed Description
This function calls either `txRxPacket1` or `txRxPacket2` function depending on the `protocol_version`. The function stores data for being written into the array for packet transmission and gets data read from rx buffer of #`port_num` port by `txPacket` and `rxPacket` functions. When `txPacket` function succeeds to communicate, it will continue to `rxPacket` and finishes the process if the packet succeeds to be received. In particular, the group handler functions for write, such as SyncWrite, and BulkWrite, don’t use `rxPacket` so the function finishes its operation immediately after the 'txPacket2'. Before the `rxPacket`, it sets packet timeout if the instruction of received packet is for read. The communication result and the hardware error are available when the function is terminated.
##### ping
- Syntax
```c
void ping (int port_num, int protocol_version, int id)
- Parameters
Parameters | Description |
---|---|
port_num | Port number |
protocol_version | Protocol version |
id | DYNAMIXEL ID |
-
Detailed Description
This function calls either
ping1
orping2
function depending on theprotocol_version
. The function usespingGetModelNum
without requesting DYNAMIXEL to send its the model number. The communication result and the hardware error are available when the function is terminated.
pingGetModelNum
- Syntax ```c int pingGetModelNum (int port_num, int protocol_version, int id)
- Parameters
| Parameters | Description |
|:-----------------|:-----------------|
| port_num | Port number |
| protocol_version | Protocol version |
| id | DYNAMIXEL ID |
- Detailed Description
This function calls either `pingGetModelNum1` or `pingGetModelNum2` function depending on the `protocol_version`. The function constructs the transmission packet for ping, and stats `txRxPacket`. Then, the function tries to get the model number of the DYNAMIXEL by `readTxRx` function. When it succeeds to receive the packet, it returns the model number. The communication result and the hardware error are available when the function is terminated.
##### broadcastPing
- Syntax
```c
void broadcastPing(int port_num, int protocol_version)
- Parameters
Parameters | Description |
---|---|
port_num | Port number |
protocol_version | Protocol version |
-
Detailed Description
This function calls either
broadcastPing1
orbroadcastPing2
function depending on theprotocol_version
. The function finds all connected dynamixels and store their id in the list. The function is unavailable in protocol 1.0.
getBroadcastPingResult
- Syntax ```c bool getBroadcastPingResult(int port_num, int protocol_version, int id)
- Parameters
| Parameters | Description |
|:-----------------|:-----------------|
| port_num | Port number |
| protocol_version | Protocol version |
| id | DYNAMIXEL ID |
- Detailed Description
This function calls either `getBroadcastPingResult1` or `getBroadcastPingResult2` function depending on the `protocol_version`. The function returns whether #`id` DYNAMIXEL responded by `broadcastPing` function. The function is unavailable in protocol 1.0.
##### action
- Syntax
```c
void action(int port_num, int protocol_version, int id)
- Parameters
Parameters | Description |
---|---|
port_num | Port number |
protocol_version | Protocol version |
id | DYNAMIXEL ID |
-
Detailed Description
This function calls either
action1
oraction2
function depending on theprotocol_version
. The function pulls the trigger of sending txpacket previously set byregWriteTxOnly
orregWriteTxRx
function, usingtxRxPacket
function. The communication result and the hardware error are available when the function is terminated.
reboot
- Syntax
void reboot(int port_num, int protocol_version, int id)
- Parameters
Parameters | Description |
---|---|
port_num | Port number |
protocol_version | Protocol version |
id | DYNAMIXEL ID |
-
Detailed Description
This function calls either
reboot1
orreboot2
function depending on theprotocol_version
. The function constructs the transmission packet with reboot instruction, and startstxRxPacket
. The function may perform its role when the DYNAMIXEL stops working caused by hardware error. The communication result and the hardware error are available when the function is terminated. The function is unavailable in protocol 1.0.
factoryReset
- Syntax ```c void factoryReset(int port_num, int protocol_version, int id, int option)
- Parameters
| Parameters | Description |
|:-----------------|:-----------------|
| port_num | Port number |
| protocol_version | Protocol version |
| id | DYNAMIXEL ID |
| option | Reset option |
- Detailed Description
This function calls either `factoryReset1` or `factoryReset2` function depending on the `protocol_version`. The function constructs the transmission packet for reset DYNAMIXEL, and starts `txRxPacket`. The resets targeted DYNAMIXEL's settings to the factory default settings. The `option` indicates the range of which items on the control table should be reset: `0xFF` for resetting all values, `0x01` for resetting all values except ID, `0x02` for resetting all values except ID and Baudrate. The communication result and the hardware error are available when the function is terminated. In protocol 1.0, `option` is selectable with only full-reset mode `0x00`.
##### readTx
- Syntax
```c
void readTx(int port_num, int protocol_version, int id, int address, int length)
- Parameters
Parameters | Description |
---|---|
port_num | Port number |
protocol_version | Protocol version |
id | DYNAMIXEL ID |
address | Address on the control table of DYNAMIXEL |
length | Packet length |
-
Detailed Description
This function calls either
readTx1
orreadTx2
function depending on theprotocol_version
. The function constructs the transmission packet with read instruction, and startstxPacket
. Then the function callssetPacketTimeout
function when packet transmission succeeds. The function can’t control more than one DYNAMIXEL at once. The communication result and the hardware error are available when the function is terminated.
readRx
- Syntax
void readRx(int port_num, int protocol_version, int length)
- Parameters
Parameters | Description |
---|---|
port_num | Port number |
protocol_version | Protocol version |
length | Packet length |
-
Detailed Description
This function calls either
readRx1
orreadRx2
function depending on theprotocol_version
. The function callsrxPacket2
function and gets the packet from read data storage if the communication succeeds. The communication result and the hardware error are available when the function is terminated.
readTxRx
- Syntax
void readTxRx(int port_num, int protocol_version, int id, int address, int length)
- Parameters
Parameters | Description |
---|---|
port_num | Port number |
protocol_version | Protocol version |
id | DYNAMIXEL ID |
address | Address on the control table of DYNAMIXEL |
length | Packet length |
-
Detailed Description
This function calls either
readTxRx1
orreadTxRx2
function depending on theprotocol_version
. The function callsreadTx
function andreadRx
function.readRx
function will be called whenreadTx
succeeds. The communication result and the hardware error are available when the function is terminated.
read1ByteTx
- Syntax
void read1ByteTx(int port_num, int protocol_version, int id, int address)
- Parameters
Parameters | Description |
---|---|
port_num | Port number |
protocol_version | Protocol version |
id | DYNAMIXEL ID |
address | Address on the control table of DYNAMIXEL |
-
Detailed Description
This function calls either
read1ByteTx1
orread1ByteTx2
function depending on theprotocol_version
. The function callsreadTx
function to send 1 Byte read intended packet transmission. The communication result and the hardware error are available when the function is terminated.
read1ByteRx
- Syntax
byte read1ByteRx(int port_num, int protocol_version)
- Parameters
Parameters | Description |
---|---|
port_num | Port number |
protocol_version | Protocol version |
-
Detailed Description
This function calls either
read1ByteRx1
orread1ByteRx2
function depending on theprotocol_version
. The function callsreadRx
function to receive response packet of 1 Byte read intended packet transmission. The communication result and the hardware error are available when the function is terminated.
read1ByteTxRx
- Syntax
byte read1ByteTxRx(int port_num, int protocol_version, int id, int address)
- Parameters
Parameters | Description |
---|---|
port_num | Port number |
protocol_version | Protocol version |
id | DYNAMIXEL ID |
address | Address on the control table of DYNAMIXEL |
-
Detailed Description
This function calls either
read1ByteTxRx1
orread1ByteTxRx2
function depending on theprotocol_version
. The function callsreadTxRx
function to read 1 Byte data from DYNAMIXEL. The communication result and the hardware error are available when the function is terminated.
read2ByteTx
- Syntax
void read2ByteTx(int port_num, int protocol_version, int id, int address)
- Parameters
Parameters | Description |
---|---|
port_num | Port number |
protocol_version | Protocol version |
id | DYNAMIXEL ID |
address | Address on the control table of DYNAMIXEL |
-
Detailed Description
This function calls either
read2ByteTx1
orread2ByteTx2
function depending on theprotocol_version
. The function callsreadTx
function to send 2 Byte read intended packet transmission. The communication result and the hardware error are available when the function is terminated.
read2ByteRx
- Syntax
int read2ByteRx(int port_num, int protocol_version)
- Parameters
Parameters | Description |
---|---|
port_num | Port number |
protocol_version | Protocol version |
-
Detailed Description
This function calls either
read2ByteRx1
orread2ByteRx2
function depending on theprotocol_version
. The function callsreadRx
function to receive response packet of 2 Byte read intended packet transmission. The communication result and the hardware error are available when the function is terminated.
read2ByteTxRx
- Syntax
int read2ByteTxRx(int port_num, int protocol_version, int id, int address)
- Parameters
Parameters | Description |
---|---|
port_num | Port number |
protocol_version | Protocol version |
id | DYNAMIXEL ID |
address | Address on the control table of DYNAMIXEL |
-
Detailed Description
This function calls either
read2ByteTxRx1
orread2ByteTxRx2
function depending on theprotocol_version
. The function callsreadTxRx
function to read 2 Byte data from DYNAMIXEL. The communication result and the hardware error are available when the function is terminated.
read4ByteTx
- Syntax
void read4ByteTx(int port_num, int protocol_version, int id, int address)
- Parameters
Parameters | Description |
---|---|
port_num | Port number |
protocol_version | Protocol version |
id | DYNAMIXEL ID |
address | Address on the control table of DYNAMIXEL |
-
Detailed Description
This function calls either
read4ByteTx1
orread4ByteTx2
function depending on theprotocol_version
. The function callsreadTx
function to send 4 Byte read intended packet transmission. The communication result and the hardware error are available when the function is terminated. The function is unavailable in protocol 1.0.
read4ByteRx
- Syntax
int read4ByteRx(int port_num, int protocol_version)
- Parameters
Parameters | Description |
---|---|
port_num | Port number |
protocol_version | Protocol version |
-
Detailed Description
This function calls either
read4ByteRx1
orread4ByteRx2
function depending on theprotocol_version
. The function callsreadRx
function to receive response packet of 4 Byte read intended packet transmission. The communication result and the hardware error are available when the function is terminated. The function is unavailable in protocol 1.0.
read4ByteTxRx
- Syntax
int read4ByteTxRx(int port_num, int protocol_version, UIN8_T id, int address)
- Parameters
Parameters | Description |
---|---|
port_num | Port number |
protocol_version | Protocol version |
id | DYNAMIXEL ID |
address | Address on the control table of DYNAMIXEL |
-
Detailed Description
This function calls either
read4ByteTxRx1
orread4ByteTxRx2
function depending on theprotocol_version
. The function callsreadTxRx
function to read 4 Byte data from DYNAMIXEL. The communication result and the hardware error are available when the function is terminated. The function is unavailable in protocol 1.0.
writeTxOnly
- Syntax
void writeTxOnly(int port_num, int protocol_version, int id, int address, int length)
- Parameters
Parameters | Description |
---|---|
port_num | Port number |
protocol_version | Protocol version |
id | DYNAMIXEL ID |
address | Address on the control table of DYNAMIXEL |
length | Packet length |
-
Detailed Description
This function calls either
writeTxOnly1
orwriteTxOnly2
function depending on theprotocol_version
. The function constructs the transmission packet with write instruction, and startstxPacket
. The communication result and the hardware error are available when the function is terminated.
writeTxRx
- Syntax
void writeTxRx(int port_num, int protocol_version, int id, int address, int length)
- Parameters
Parameters | Description |
---|---|
port_num | Port number |
protocol_version | Protocol version |
id | DYNAMIXEL ID |
address | Address on the control table of DYNAMIXEL |
length | Packet length |
-
Detailed Description
This function calls either
writeTxRx1
orwriteTxRx2
function depending on theprotocol_version
. The function constructs the transmission packet with write instruction, and startstxRxPacket
. The communication result and the hardware error are available when the function is terminated.
write1ByteTxOnly
- Syntax
void write1ByteTxOnly(int port_num, int protocol_version, int id, int address, int data)
- Parameters
Parameters | Description |
---|---|
port_num | Port number |
protocol_version | Protocol version |
id | DYNAMIXEL ID |
address | Address on the control table of DYNAMIXEL |
data | Data for write |
-
Detailed Description
This function calls either
write1ByteTxOnly1
orwrite1ByteTxOnly2
function depending on theprotocol_version
. The function callswriteTxOnly
function to send 1 Byte write intended packet transmission. The communication result and the hardware error are available when the function is terminated.
write1ByteTxRx
- Syntax
void write1ByteTxRx(int port_num, int protocol_version, int id, int address, int data)
- Parameters
Parameters | Description |
---|---|
port_num | Port number |
protocol_version | Protocol version |
id | DYNAMIXEL ID |
address | Address on the control table of DYNAMIXEL |
data | Data for write |
-
Detailed Description
This function calls either
write1ByteTxRx1
orwrite1ByteTxRx2
function depending on theprotocol_version
. The function callswriteTxRx
function to send 1 Byte write intended packet transmission (and reception). The communication result and the hardware error are available when the function is terminated.
write2ByteTxOnly
- Syntax
void write2ByteTxOnly(int port_num, int protocol_version, int id, int address, int data)
- Parameters
Parameters | Description |
---|---|
port_num | Port number |
protocol_version | Protocol version |
id | DYNAMIXEL ID |
address | Address on the control table of DYNAMIXEL |
data | Data for write |
-
Detailed Description
This function calls either
write2ByteTxOnly1
orwrite2ByteTxOnly2
function depending on theprotocol_version
. The function callswriteTxOnly
function to send 2 Byte write intended packet transmission. The communication result and the hardware error are available when the function is terminated.
write2ByteTxRx
- Syntax
void write2ByteTxRx(int port_num, int protocol_version, int id, int address, int data)
- Parameters
Parameters | Description |
---|---|
port_num | Port number |
protocol_version | Protocol version |
id | DYNAMIXEL ID |
address | Address on the control table of DYNAMIXEL |
data | Data for write |
-
Detailed Description
This function calls either
write2ByteTxRx1
orwrite2ByteTxRx2
function depending on theprotocol_version
. The function callswriteTxRx
function to send 2 Byte write intended packet transmission (and reception). The communication result and the hardware error are available when the function is terminated.
write4ByteTxOnly
- Syntax
void write4ByteTxOnly(int port_num, int protocol_version, int id, int address, int data)
- Parameters
Parameters | Description |
---|---|
port_num | Port number |
protocol_version | Protocol version |
id | DYNAMIXEL ID |
address | Address on the control table of DYNAMIXEL |
data | Data for write |
-
Detailed Description
This function calls either
write4ByteTxOnly1
orwrite4ByteTxOnly2
function depending on theprotocol_version
. The function callswriteTxOnly
function to send 4 Byte write intended packet transmission. The communication result and the hardware error are available when the function is terminated. The function is unavailable in protocol 1.0.
write4ByteTxRx
- Syntax
void write4ByteTxRx(int port_num, int protocol_version, int id, int address)
- Parameters
Parameters | Description |
---|---|
port_num | Port number |
protocol_version | Protocol version |
id | DYNAMIXEL ID |
address | Address on the control table of DYNAMIXEL |
-
Detailed Description
This function calls either
write4ByteTxRx1
orwrite4ByteTxRx2
function depending on theprotocol_version
. The function callswriteTxRx
function to send 4 Byte write intended packet transmission (and reception). The communication result and the hardware error are available when the function is terminated. The function is unavailable in protocol 1.0.
regWriteTxOnly
- Syntax
void regWriteTxOnly(int port_num, int protocol_version, int id, int address, int length)
- Parameters
Parameters | Description |
---|---|
port_num | Port number |
protocol_version | Protocol version |
id | DYNAMIXEL ID |
address | Address on the control table of DYNAMIXEL |
length | Packet length |
-
Detailed Description
This function calls either
RegWriteTxOnly1
orRegWriteTxOnly2
function depending on theprotocol_version
. The function intends simultaneous control of more than one DYNAMIXEL. The function writes the data without requesting an action of DYNAMIXEL. The DYNAMIXEL works when the triggeraction
function is executed. The function needs previous setting of the data to write on the DYNAMIXEL. The communication result and the hardware error are available when the function is terminated.
regWriteTxRx
- Syntax
void regWriteTxRx(int port_num, int protocol_version, int id, int address, int length)
- Parameters
Parameters | Description |
---|---|
port_num | Port number |
protocol_version | Protocol version |
id | DYNAMIXEL ID |
address | Address on the control table of DYNAMIXEL |
length | Packet length |
-
Detailed Description
This function calls either
regWriteTxRx1
orregWriteTxRx2
function depending on theprotocol_version
. The function intends simultaneous multiple DYNAMIXEL’s control. The function writes the data without requesting an action of DYNAMIXEL. The DYNAMIXEL works when the triggeraction
function is executed. The function needs previous setting of the data to write on the DYNAMIXEL. The communication result and the hardware error are available when the function is terminated.
syncReadTx
- Syntax
void syndReadTx(int port_num, int protocol_version, int address, int data_length, int param_length)
- Parameters
Parameters | Description |
---|---|
port_num | Port number |
protocol_version | Protocol version |
address | Address on the control table of DYNAMIXEL |
data_length | Data length |
param_length | Parameter length |
-
Detailed Description
This function calls either
syncReadTx1
orsyncReadTx2
function depending on theprotocol_version
. The function intends simultanoues multiple DYNAMIXEL’s control by reading same length of data from the same address on the DYNAMIXEL control table. The function constructs the transmission packet with sync read instruction, and starts ‘txPacket2’. Then the function callssetPacketTimeout
function whentxPacket
succeeds. The communication result and the hardware error are available when the function is terminated. The function is unavailable in protocol 1.0.
syncWriteTxOnly
- Syntax
void syncWriteTxOnly(int port_num, int protocol_version, int start_address, int data_length, int param_length)
- Parameters
Parameters | Description |
---|---|
port_num | Port number |
protocol_version | Protocol version |
start_address | Address on the control table of DYNAMIXEL |
data_length | Data length |
param_length | Parameter length |
-
Detailed Description
This function calls either
syncWriteTxOnly1
orsyncWriteTxOnly2
function depending on theprotocol_version
. The function intends simultaneous multiple DYNAMIXEL’s control by writing same length of data to the same address on the DYNAMIXEL control table. The function constructs the transmission packet with sync write instruction, and startstxRxPacket
. The communication result and the hardware error are available when the function is terminated.
bulkReadTx
- Syntax
void bulkReadTx(int port_num, int protocol_version, int param_length)
- Parameters
Parameters | Description |
---|---|
port_num | Port number |
protocol_version | Protocol version |
param_length | Parameter length |
-
Detailed Description
This function calls either
bulkReadTx1
orbulkReadTx2
function depending on theprotocol_version
. The function intends simultaneous multiple DYNAMIXEL’s control by writing different length of data to the different address on the DYNAMIXEL control table. The function constructs the transmission packet with bulk read instruction, and startstxPacket
. Then the function callssetPacketTimeout
function whentxPacket
succeeds. The communication result and the hardware error are available when the function is terminated.
bulkWriteTxOnly
- Syntax
void bulkWriteTxOnly(int port_num, int protocol_version, int param_length)
- Parameters
Parameters | Description |
---|---|
port_num | Port number |
protocol_version | Protocol version |
param_length | Parameter length |
-
Detailed Description
This function calls either
bulkWriteTxOnly1
orbulkWriteTxOnly2
function depending on theprotocol_version
. The function intends simultaneous multiple DYNAMIXEL’s control by writing different length of data from the different address on the DYNAMIXEL control table. The function constructs the transmission packet with bulk write instruction, and startsTxRxPacket
. The communication result and the hardware error are available when the function is terminated. The function is unavailable in protocol 1.0.