Skip to content
Snippets Groups Projects
Protocol1PacketHandler.c 24.4 KiB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602 603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656 657 658 659 660 661 662 663 664 665 666 667 668 669 670 671 672 673 674 675 676 677 678 679 680 681 682 683 684 685 686 687 688 689 690 691 692 693 694 695 696 697 698 699 700 701 702 703 704 705 706 707 708 709 710 711 712 713 714 715 716 717 718 719 720 721 722 723 724 725 726 727 728 729 730 731
/*
* Protocol1PacketHandler.c
*
*  Created on: 2016. 5. 4.
*      Author: leon
*/
#if defined(_WIN32) || defined(_WIN64)
#define WINDLLEXPORT
#endif

#include <string.h>
#include <stdlib.h>
#include "dynamixel_sdk/Protocol1PacketHandler.h"

#define TXPACKET_MAX_LEN    (250)
#define RXPACKET_MAX_LEN    (250)

///////////////// for Protocol 1.0 Packet /////////////////
#define PKT_HEADER0             0
#define PKT_HEADER1             1
#define PKT_ID                  2
#define PKT_LENGTH              3
#define PKT_INSTRUCTION         4
#define PKT_ERROR               4
#define PKT_PARAMETER0          5

///////////////// Protocol 1.0 Error bit /////////////////
#define ERRBIT_VOLTAGE          1       // Supplied voltage is out of the range (operating volatage set in the control table)
#define ERRBIT_ANGLE            2       // Goal position is written out of the range (from CW angle limit to CCW angle limit)
#define ERRBIT_OVERHEAT         4       // Temperature is out of the range (operating temperature set in the control table)
#define ERRBIT_RANGE            8       // Command(setting value) is out of the range for use.
#define ERRBIT_CHECKSUM         16      // Instruction packet checksum is incorrect.
#define ERRBIT_OVERLOAD         32      // The current load cannot be controlled by the set torque.
#define ERRBIT_INSTRUCTION      64      // Undefined instruction or delivering the action command without the reg_write command.


void PrintTxRxResult1(int result)
{
    switch (result)
    {
    case COMM_SUCCESS:
        printf("[TxRxResult] Communication success.\n");
        break;

    case COMM_PORT_BUSY:
        printf("[TxRxResult] Port is in use!\n");
        break;

    case COMM_TX_FAIL:
        printf("[TxRxResult] Failed transmit instruction packet!\n");
        break;

    case COMM_RX_FAIL:
        printf("[TxRxResult] Failed get status packet from device!\n");
        break;

    case COMM_TX_ERROR:
        printf("[TxRxResult] Incorrect instruction packet!\n");
        break;

    case COMM_RX_WAITING:
        printf("[TxRxResult] Now recieving status packet!\n");
        break;

    case COMM_RX_TIMEOUT:
        printf("[TxRxResult] There is no status packet!\n");
        break;

    case COMM_RX_CORRUPT:
        printf("[TxRxResult] Incorrect status packet!\n");
        break;

    case COMM_NOT_AVAILABLE:
        printf("[TxRxResult] Protocol does not support This function!\n");
        break;

    default:
        break;
    }
}

void PrintRxPacketError1(UINT8_T error)
{
    if (error & ERRBIT_VOLTAGE)
        printf("[RxPacketError] Input voltage error!\n");

    if (error & ERRBIT_ANGLE)
        printf("[RxPacketError] Angle limit error!\n");

    if (error & ERRBIT_OVERHEAT)
        printf("[RxPacketError] Overheat error!\n");

    if (error & ERRBIT_RANGE)
        printf("[RxPacketError] Out of range error!\n");

    if (error & ERRBIT_CHECKSUM)
        printf("[RxPacketError] Checksum error!\n");

    if (error & ERRBIT_OVERLOAD)
        printf("[RxPacketError] Overload error!\n");

    if (error & ERRBIT_INSTRUCTION)
        printf("[RxPacketError] Instruction code error!\n");
}

int GetLastTxRxResult1(int port_num)
{
    return packetData[port_num].communication_result_;
}
UINT8_T GetLastRxPacketError1(int port_num)
{
    return packetData[port_num].error_;
}

void SetDataWrite1(int port_num, UINT16_T data_length, UINT16_T data_pos, UINT32_T data)
{
    packetData[port_num].data_write_ = (UINT8_T *)realloc(packetData[port_num].data_write_, (data_pos + data_length) * sizeof(UINT8_T));

    switch (data_length)
    {
    case 1:
        packetData[port_num].data_write_[data_pos + 0] = DXL_LOBYTE(DXL_LOWORD(data));
        break;

    case 2:
        packetData[port_num].data_write_[data_pos + 0] = DXL_LOBYTE(DXL_LOWORD(data));
        packetData[port_num].data_write_[data_pos + 1] = DXL_HIBYTE(DXL_LOWORD(data));
        break;

    default:
        printf("[Set Data for Write] failed");
        break;
    }
}

UINT32_T GetDataRead1(int port_num, UINT16_T data_length, UINT16_T data_pos)
{
    switch (data_length)
    {
    case 1:
        return packetData[port_num].data_read_[data_pos + 0];

    case 2:
        return DXL_MAKEWORD(packetData[port_num].data_read_[data_pos + 0], packetData[port_num].data_read_[data_pos + 1]);

    default:
        printf("[Set Data Read] failed... ");
        return 0;
    }
}

void TxPacket1(int port_num)
{
    int _idx;

    UINT8_T _checksum = 0;
    UINT8_T _total_packet_length = packetData[port_num].txpacket_[PKT_LENGTH] + 4; // 4: HEADER0 HEADER1 ID LENGTH
    UINT8_T _written_packet_length = 0;

    if (is_using_[port_num])
    {
        packetData[port_num].communication_result_ = COMM_PORT_BUSY;
        return ;
    }
    is_using_[port_num] = true;

    // check max packet length
    if (_total_packet_length > TXPACKET_MAX_LEN)
    {
        is_using_[port_num] = false;
        packetData[port_num].communication_result_ = COMM_TX_ERROR;
        return;
    }

    // make packet header
    packetData[port_num].txpacket_[PKT_HEADER0] = 0xFF;
    packetData[port_num].txpacket_[PKT_HEADER1] = 0xFF;

    // add a checksum to the packet
    for (_idx = 2; _idx < _total_packet_length - 1; _idx++)   // except header, checksum
        _checksum += packetData[port_num].txpacket_[_idx];
    packetData[port_num].txpacket_[_total_packet_length - 1] = ~_checksum;

    // tx packet
    ClearPort(port_num);
    _written_packet_length = WritePort(port_num, packetData[port_num].txpacket_, _total_packet_length);
    if (_total_packet_length != _written_packet_length)
    {
        is_using_[port_num] = false;
        packetData[port_num].communication_result_ = COMM_TX_FAIL;
        return;
    }

    packetData[port_num].communication_result_ = COMM_SUCCESS;
}

void RxPacket1(int port_num)
{
    UINT8_T _idx, _s;
    int _i;

    packetData[port_num].communication_result_ = COMM_TX_FAIL;

    UINT8_T _checksum = 0;
    UINT8_T _rx_length = 0;
    UINT8_T _wait_length = 6;    // minimum length ( HEADER0 HEADER1 ID LENGTH ERROR CHKSUM )

    while (true)
    {
        _rx_length += ReadPort(port_num, &packetData[port_num].rxpacket_[_rx_length], _wait_length - _rx_length);
        if (_rx_length >= _wait_length)
        {
            _idx = 0;

            // find packet header
            for (_idx = 0; _idx < (_rx_length - 1); _idx++)
            {
                if (packetData[port_num].rxpacket_[_idx] == 0xFF && packetData[port_num].rxpacket_[_idx + 1] == 0xFF)
                    break;
            }

            if (_idx == 0)   // found at the beginning of the packet
            {
                if (packetData[port_num].rxpacket_[PKT_ID] > 0xFD ||                   // unavailable ID
                    packetData[port_num].rxpacket_[PKT_LENGTH] > RXPACKET_MAX_LEN ||   // unavailable Length
                    packetData[port_num].rxpacket_[PKT_ERROR] >= 0x64)                 // unavailable Error
                {
                    // remove the first byte in the packet
                    for (_s = 0; _s < _rx_length - 1; _s++)
                        packetData[port_num].rxpacket_[_s] = packetData[port_num].rxpacket_[1 + _s];
                    //memcpy(&rxpacket[0], &rxpacket[_idx], _rx_length - _idx);
                    _rx_length -= 1;
                    continue;
                }

                // re-calculate the exact length of the rx packet
                _wait_length = packetData[port_num].rxpacket_[PKT_LENGTH] + PKT_LENGTH + 1;
                if (_rx_length < _wait_length)
                {
                    // check timeout
                    if (IsPacketTimeout(port_num) == true)
                    {
                        if (_rx_length == 0)
                            packetData[port_num].communication_result_ = COMM_RX_TIMEOUT;
                        else
                            packetData[port_num].communication_result_ = COMM_RX_CORRUPT;
                        break;
                    }
                    else
                        continue;
                }

                // calculate checksum
                for (_i = 2; _i < _wait_length - 1; _i++)   // except header, checksum
                    _checksum += packetData[port_num].rxpacket_[_i];
                _checksum = ~_checksum;

                // verify checksum
                if (packetData[port_num].rxpacket_[_wait_length - 1] == _checksum)
                    packetData[port_num].communication_result_ = COMM_SUCCESS;
                else
                    packetData[port_num].communication_result_ = COMM_RX_CORRUPT;
                break;
            }
            else
            {
                // remove unnecessary packets
                for (_s = 0; _s < _rx_length - _idx; _s++)
                    packetData[port_num].rxpacket_[_s] = packetData[port_num].rxpacket_[_idx + _s];
                //memcpy(&rxpacket[0], &rxpacket[_idx], _rx_length - _idx);
                _rx_length -= _idx;
            }
        }
        else
        {
            // check timeout
            if (IsPacketTimeout(port_num) == true)
            {
                if (_rx_length == 0)
                    packetData[port_num].communication_result_ = COMM_RX_TIMEOUT;
                else
                    packetData[port_num].communication_result_ = COMM_RX_CORRUPT;
                break;
            }
        }
    }
    is_using_[port_num] = false;
}

// NOT for BulkRead instruction
void TxRxPacket1(int port_num)
{
    packetData[port_num].communication_result_ = COMM_TX_FAIL;

    // tx packet
    TxPacket1(port_num);

    if (packetData[port_num].communication_result_ != COMM_SUCCESS)
        return;

    // (ID == Broadcast ID && NOT BulkRead) == no need to wait for status packet
    // (Instruction == Action) == no need to wait for status packet
    if ((packetData[port_num].txpacket_[PKT_ID] == BROADCAST_ID && packetData[port_num].txpacket_[PKT_INSTRUCTION] != INST_BULK_READ) ||
        (packetData[port_num].txpacket_[PKT_INSTRUCTION] == INST_ACTION))
    {
        is_using_[port_num] = false;
        return;
    }

    // set packet timeout
    if (packetData[port_num].txpacket_[PKT_INSTRUCTION] == INST_READ)
        SetPacketTimeout(port_num, (UINT16_T)(packetData[port_num].txpacket_[PKT_PARAMETER0 + 1] + 6));
    else
        SetPacketTimeout(port_num, (UINT16_T)6);

    // rx packet
    RxPacket1(port_num);
    // check txpacket ID == rxpacket ID
    if (packetData[port_num].txpacket_[PKT_ID] != packetData[port_num].rxpacket_[PKT_ID])
        RxPacket1(port_num);

    if (packetData[port_num].communication_result_ == COMM_SUCCESS && packetData[port_num].txpacket_[PKT_ID] != BROADCAST_ID)
    {
        if (packetData[port_num].error_ != 0)
            packetData[port_num].error_ = (UINT8_T)packetData[port_num].rxpacket_[PKT_ERROR];
    }
}

void Ping1(int port_num, UINT8_T id)
{
    PingGetModelNum1(port_num, id);
}

UINT16_T PingGetModelNum1(int port_num, UINT8_T id)
{
    packetData[port_num].communication_result_ = COMM_TX_FAIL;

    packetData[port_num].txpacket_ = (UINT8_T *)malloc(6);
    packetData[port_num].rxpacket_ = (UINT8_T *)malloc(6);

    if (id >= BROADCAST_ID)
    {
        packetData[port_num].communication_result_ = COMM_NOT_AVAILABLE;
        return 0;
    }

    packetData[port_num].txpacket_[PKT_ID] = id;
    packetData[port_num].txpacket_[PKT_LENGTH] = 2;
    packetData[port_num].txpacket_[PKT_INSTRUCTION] = INST_PING;

    TxRxPacket1(port_num);
    if (packetData[port_num].communication_result_ == COMM_SUCCESS)
    {
        ReadTxRx1(port_num, id, 0, 2);  // Address 0 : Model Number
        if (packetData[port_num].communication_result_ == COMM_SUCCESS)
            return DXL_MAKEWORD(packetData[port_num].data_read_[0], packetData[port_num].data_read_[1]);
    }

    return 0;
}

void BroadcastPing1(int port_num)
{
    packetData[port_num].communication_result_ = COMM_NOT_AVAILABLE;
}

bool GetBroadcastPingResult1(int port_num, int id)
{
    return false;
}

void Action1(int port_num, UINT8_T id)
{
    packetData[port_num].txpacket_ = (UINT8_T *)malloc(6);

    packetData[port_num].txpacket_[PKT_ID] = id;
    packetData[port_num].txpacket_[PKT_LENGTH] = 2;
    packetData[port_num].txpacket_[PKT_INSTRUCTION] = INST_ACTION;

    TxRxPacket1(port_num);
}

void Reboot1(int port_num, UINT8_T id)
{
    packetData[port_num].communication_result_ = COMM_NOT_AVAILABLE;
}

void FactoryReset1(int port_num, UINT8_T id, UINT8_T option)
{
    packetData[port_num].txpacket_ = (UINT8_T *)malloc(6);
    packetData[port_num].rxpacket_ = (UINT8_T *)malloc(6);

    packetData[port_num].txpacket_[PKT_ID] = id;
    packetData[port_num].txpacket_[PKT_LENGTH] = 2;
    packetData[port_num].txpacket_[PKT_INSTRUCTION] = INST_FACTORY_RESET;

    TxRxPacket1(port_num);
}

void ReadTx1(int port_num, UINT8_T id, UINT16_T address, UINT16_T length)
{
    packetData[port_num].communication_result_ = COMM_TX_FAIL;

    packetData[port_num].txpacket_ = (UINT8_T *)malloc(8);

    if (id >= BROADCAST_ID) 
    {
        packetData[port_num].communication_result_ = COMM_NOT_AVAILABLE;
        return;
    }

    packetData[port_num].txpacket_[PKT_ID] = id;
    packetData[port_num].txpacket_[PKT_LENGTH] = 4;
    packetData[port_num].txpacket_[PKT_INSTRUCTION] = INST_READ;
    packetData[port_num].txpacket_[PKT_PARAMETER0 + 0] = (UINT8_T)address;
    packetData[port_num].txpacket_[PKT_PARAMETER0 + 1] = (UINT8_T)length;

    TxPacket1(port_num);

    // set packet timeout
    if (packetData[port_num].communication_result_ == COMM_SUCCESS)
        SetPacketTimeout(port_num, (UINT16_T)(length + 6));
}

void ReadRx1(int port_num, UINT16_T length)
{
    UINT8_T _s;

    packetData[port_num].communication_result_ = COMM_TX_FAIL;
    packetData[port_num].rxpacket_ = (UINT8_T *)malloc(RXPACKET_MAX_LEN);

    RxPacket1(port_num);
    if (packetData[port_num].communication_result_ == COMM_SUCCESS)
    {
        if (packetData[port_num].error_ != 0)
            packetData[port_num].error_ = (UINT8_T)packetData[port_num].rxpacket_[PKT_ERROR];
        for (_s = 0; _s < length; _s++)
            packetData[port_num].data_read_[_s] = packetData[port_num].rxpacket_[PKT_PARAMETER0 + _s];
        //memcpy(data, &rxpacket[PKT_PARAMETER0], length);
    }

    free(packetData[port_num].rxpacket_);
}

void ReadTxRx1(int port_num, UINT8_T id, UINT16_T address, UINT16_T length)
{
    UINT8_T _s;
    packetData[port_num].communication_result_ = COMM_TX_FAIL;

    packetData[port_num].txpacket_ = (UINT8_T *)malloc(8);
    packetData[port_num].rxpacket_ = (UINT8_T *)malloc(RXPACKET_MAX_LEN);

    if (id >= BROADCAST_ID)
    {
        packetData[port_num].communication_result_ = COMM_NOT_AVAILABLE;
        return;
    }

    packetData[port_num].txpacket_[PKT_ID] = id;
    packetData[port_num].txpacket_[PKT_LENGTH] = 4;
    packetData[port_num].txpacket_[PKT_INSTRUCTION] = INST_READ;
    packetData[port_num].txpacket_[PKT_PARAMETER0 + 0] = (UINT8_T)address;
    packetData[port_num].txpacket_[PKT_PARAMETER0 + 1] = (UINT8_T)length;

    TxRxPacket1(port_num);
    if (packetData[port_num].communication_result_ == COMM_SUCCESS)
    {
        if (packetData[port_num].error_ != 0)
            packetData[port_num].error_ = (UINT8_T)packetData[port_num].rxpacket_[PKT_ERROR];
        for (_s = 0; _s < length; _s++)
            packetData[port_num].data_read_[_s] = packetData[port_num].rxpacket_[PKT_PARAMETER0 + _s];
        //memcpy(data, &rxpacket[PKT_PARAMETER0], length);
    }

    free(packetData[port_num].rxpacket_);
}

void Read1ByteTx1(int port_num, UINT8_T id, UINT16_T address)
{
    ReadTx1(port_num, id, address, 1);
}
UINT8_T Read1ByteRx1(int port_num)
{
    packetData[port_num].data_read_[0] = 0;
    ReadRx1(port_num, 1);
    if (packetData[port_num].communication_result_ == COMM_SUCCESS)
        return packetData[port_num].data_read_[0];
    return 0;
}
UINT8_T Read1ByteTxRx1(int port_num, UINT8_T id, UINT16_T address)
{
    packetData[port_num].data_read_[0] = 0;
    ReadTxRx1(port_num, id, address, 1);
    if (packetData[port_num].communication_result_ == COMM_SUCCESS)
        return packetData[port_num].data_read_[0];
    return 0;
}

void Read2ByteTx1(int port_num, UINT8_T id, UINT16_T address)
{
    ReadTx1(port_num, id, address, 2);
}
UINT16_T Read2ByteRx1(int port_num)
{
    packetData[port_num].data_read_[0] = 0;
    packetData[port_num].data_read_[1] = 0;
    ReadRx1(port_num, 2);
    if (packetData[port_num].communication_result_ == COMM_SUCCESS)
        return DXL_MAKEWORD(packetData[port_num].data_read_[0], packetData[port_num].data_read_[1]);
    return 0;
}
UINT16_T Read2ByteTxRx1(int port_num, UINT8_T id, UINT16_T address)
{
    packetData[port_num].data_read_[0] = 0;
    packetData[port_num].data_read_[1] = 0;
    ReadTxRx1(port_num, id, address, 2);

    if (packetData[port_num].communication_result_ == COMM_SUCCESS)
        return DXL_MAKEWORD(packetData[port_num].data_read_[0], packetData[port_num].data_read_[1]);

    return 0;
}

void Read4ByteTx1(int port_num, UINT8_T id, UINT16_T address)
{
    packetData[port_num].communication_result_ = COMM_NOT_AVAILABLE;
}
UINT32_T Read4ByteRx1(int port_num)
{
    packetData[port_num].communication_result_ = COMM_NOT_AVAILABLE;
    return 0;
}
UINT32_T Read4ByteTxRx1(int port_num, UINT8_T id, UINT16_T address)
{
    packetData[port_num].communication_result_ = COMM_NOT_AVAILABLE;
    return 0;
}

void WriteTxOnly1(int port_num, UINT8_T id, UINT16_T address, UINT16_T length)
{
    UINT8_T _s;

    packetData[port_num].communication_result_ = COMM_TX_FAIL;

    packetData[port_num].txpacket_ = (UINT8_T *)malloc(length + 7);

    packetData[port_num].txpacket_[PKT_ID] = id;
    packetData[port_num].txpacket_[PKT_LENGTH] = length + 3;
    packetData[port_num].txpacket_[PKT_INSTRUCTION] = INST_WRITE;
    packetData[port_num].txpacket_[PKT_PARAMETER0] = (UINT8_T)address;

    for (_s = 0; _s < length; _s++)
        packetData[port_num].txpacket_[PKT_PARAMETER0 + 1 + _s] = packetData[port_num].data_write_[_s];
    //memcpy(&txpacket[PKT_PARAMETER0+1], data, length);

    TxPacket1(port_num);
    is_using_[port_num] = false;

    free(packetData[port_num].txpacket_);
}

void WriteTxRx1(int port_num, UINT8_T id, UINT16_T address, UINT16_T length)
{
    UINT8_T _s;

    packetData[port_num].communication_result_ = COMM_TX_FAIL;

    packetData[port_num].txpacket_ = (UINT8_T *)malloc(length + 6);
    packetData[port_num].rxpacket_ = (UINT8_T *)malloc(6);

    packetData[port_num].txpacket_[PKT_ID] = id;
    packetData[port_num].txpacket_[PKT_LENGTH] = length + 3;
    packetData[port_num].txpacket_[PKT_INSTRUCTION] = INST_WRITE;
    packetData[port_num].txpacket_[PKT_PARAMETER0] = (UINT8_T)address;

    for (_s = 0; _s < length; _s++)
        packetData[port_num].txpacket_[PKT_PARAMETER0 + 1 + _s] = packetData[port_num].data_write_[_s];
    //memcpy(&txpacket[PKT_PARAMETER0+1], data, length);

    TxRxPacket1(port_num);

    free(packetData[port_num].txpacket_);
}

void Write1ByteTxOnly1(int port_num, UINT8_T id, UINT16_T address, UINT8_T data)
{
    packetData[port_num].data_write_ = (UINT8_T *)realloc(packetData[port_num].data_write_, 1 * sizeof(UINT8_T));
    packetData[port_num].data_write_[0] = data;
    WriteTxOnly1(port_num, id, address, 1);
}
void Write1ByteTxRx1(int port_num, UINT8_T id, UINT16_T address, UINT8_T data)
{
    packetData[port_num].data_write_ = (UINT8_T *)realloc(packetData[port_num].data_write_, 1 * sizeof(UINT8_T));
    packetData[port_num].data_write_[0] = data;
    WriteTxRx1(port_num, id, address, 1);
}

void Write2ByteTxOnly1(int port_num, UINT8_T id, UINT16_T address, UINT16_T data)
{
    packetData[port_num].data_write_ = (UINT8_T *)realloc(packetData[port_num].data_write_, 2 * sizeof(UINT8_T));
    packetData[port_num].data_write_[0] = DXL_LOBYTE(data);
    packetData[port_num].data_write_[1] = DXL_HIBYTE(data);
    WriteTxOnly1(port_num, id, address, 2);
}
void Write2ByteTxRx1(int port_num, UINT8_T id, UINT16_T address, UINT16_T data)
{
    packetData[port_num].data_write_ = (UINT8_T *)realloc(packetData[port_num].data_write_, 2 * sizeof(UINT8_T));
    packetData[port_num].data_write_[0] = DXL_LOBYTE(data);
    packetData[port_num].data_write_[1] = DXL_HIBYTE(data);
    WriteTxRx1(port_num, id, address, 2);
}

void Write4ByteTxOnly1(int port_num, UINT8_T id, UINT16_T address, UINT32_T data)
{
    packetData[port_num].communication_result_ = COMM_NOT_AVAILABLE;
}
void Write4ByteTxRx1(int port_num, UINT8_T id, UINT16_T address, UINT32_T data)
{
    packetData[port_num].communication_result_ = COMM_NOT_AVAILABLE;
}

void RegWriteTxOnly1(int port_num, UINT8_T id, UINT16_T address, UINT16_T length)
{
    UINT8_T _s;

    packetData[port_num].communication_result_ = COMM_TX_FAIL;

    packetData[port_num].txpacket_ = (UINT8_T *)malloc(length + 6);

    packetData[port_num].txpacket_[PKT_ID] = id;
    packetData[port_num].txpacket_[PKT_LENGTH] = length + 3;
    packetData[port_num].txpacket_[PKT_INSTRUCTION] = INST_REG_WRITE;
    packetData[port_num].txpacket_[PKT_PARAMETER0] = (UINT8_T)address;

    for (_s = 0; _s < length; _s++)
        packetData[port_num].txpacket_[PKT_PARAMETER0 + 1 + _s] = packetData[port_num].data_write_[_s];
    //memcpy(&txpacket[PKT_PARAMETER0+1], data, length);

     TxPacket1(port_num);
    is_using_[port_num] = false;

    free(packetData[port_num].txpacket_);
}

void RegWriteTxRx1(int port_num, UINT8_T id, UINT16_T address, UINT16_T length)
{
    UINT8_T _s;

    packetData[port_num].communication_result_ = COMM_TX_FAIL;

    packetData[port_num].txpacket_ = (UINT8_T *)malloc(length + 6);
    packetData[port_num].rxpacket_ = (UINT8_T *)malloc(6);

    packetData[port_num].txpacket_[PKT_ID] = id;
    packetData[port_num].txpacket_[PKT_LENGTH] = length + 3;
    packetData[port_num].txpacket_[PKT_INSTRUCTION] = INST_REG_WRITE;
    packetData[port_num].txpacket_[PKT_PARAMETER0] = (UINT8_T)address;

    packetData[port_num].data_write_ = (UINT8_T *)realloc(packetData[port_num].data_write_, length * sizeof(UINT8_T));

    for (_s = 0; _s < length; _s++)
        packetData[port_num].txpacket_[PKT_PARAMETER0 + 1 + _s] = packetData[port_num].data_write_[_s];
    //memcpy(&txpacket[PKT_PARAMETER0+1], data, length);

    TxRxPacket1(port_num);

    free(packetData[port_num].txpacket_);
}

void SyncReadTx1(int port_num, UINT16_T start_address, UINT16_T data_length, UINT16_T param_length)
{
    packetData[port_num].communication_result_ = COMM_NOT_AVAILABLE;
}

void SyncWriteTxOnly1(int port_num, UINT16_T start_address, UINT16_T data_length, UINT16_T param_length)
{
    UINT8_T _s;

    packetData[port_num].communication_result_ = COMM_TX_FAIL;

    packetData[port_num].txpacket_ = (UINT8_T *)malloc(param_length + 8);    // 8: HEADER0 HEADER1 ID LEN INST START_ADDR DATA_LEN ... CHKSUM
                                                               
    packetData[port_num].txpacket_[PKT_ID] = BROADCAST_ID;
    packetData[port_num].txpacket_[PKT_LENGTH] = param_length + 4; // 4: INST START_ADDR DATA_LEN ... CHKSUM
    packetData[port_num].txpacket_[PKT_INSTRUCTION] = INST_SYNC_WRITE;
    packetData[port_num].txpacket_[PKT_PARAMETER0 + 0] = start_address;
    packetData[port_num].txpacket_[PKT_PARAMETER0 + 1] = data_length;

    for (_s = 0; _s < param_length; _s++)
        packetData[port_num].txpacket_[PKT_PARAMETER0 + 2 + _s] = packetData[port_num].data_write_[_s];
    //memcpy(&txpacket[PKT_PARAMETER0+2], param, param_length);

    TxRxPacket1(port_num);

    free(packetData[port_num].txpacket_);
}

void BulkReadTx1(int port_num, UINT16_T param_length)
{
    UINT8_T _s;

    int _i;
    packetData[port_num].communication_result_ = COMM_TX_FAIL;

    packetData[port_num].txpacket_ = (UINT8_T *)malloc(param_length + 7);    // 7: HEADER0 HEADER1 ID LEN INST 0x00 ... CHKSUM

    packetData[port_num].txpacket_[PKT_ID] = BROADCAST_ID;
    packetData[port_num].txpacket_[PKT_LENGTH] = param_length + 3; // 3: INST 0x00 ... CHKSUM
    packetData[port_num].txpacket_[PKT_INSTRUCTION] = INST_BULK_READ;
    packetData[port_num].txpacket_[PKT_PARAMETER0 + 0] = 0x00;

    for (_s = 0; _s < param_length; _s++)
        packetData[port_num].txpacket_[PKT_PARAMETER0 + 1 + _s] = packetData[port_num].data_write_[_s];
        //memcpy(&txpacket[PKT_PARAMETER0+1], param, param_length);

    TxPacket1(port_num);
    if (packetData[port_num].communication_result_ == COMM_SUCCESS)
    {
        int _wait_length = 0;
        for (_i = 0; _i < param_length; _i += 3)
            _wait_length += packetData[port_num].data_write_[_i] + 7;
        SetPacketTimeout(port_num, (UINT16_T)_wait_length);
    }

    free(packetData[port_num].txpacket_);
}

void BulkWriteTxOnly1(int port_num, UINT16_T param_length)
{
    packetData[port_num].communication_result_ = COMM_NOT_AVAILABLE;
}