protocol1_packet_handler.cpp
Go to the documentation of this file.
00001 /*******************************************************************************
00002 * Copyright 2017 ROBOTIS CO., LTD.
00003 *
00004 * Licensed under the Apache License, Version 2.0 (the "License");
00005 * you may not use this file except in compliance with the License.
00006 * You may obtain a copy of the License at
00007 *
00008 *     http://www.apache.org/licenses/LICENSE-2.0
00009 *
00010 * Unless required by applicable law or agreed to in writing, software
00011 * distributed under the License is distributed on an "AS IS" BASIS,
00012 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013 * See the License for the specific language governing permissions and
00014 * limitations under the License.
00015 *******************************************************************************/
00016 
00017 /* Author: zerom, Ryu Woon Jung (Leon) */
00018 
00019 #if defined(__linux__)
00020 #include "protocol1_packet_handler.h"
00021 #elif defined(__APPLE__)
00022 #include "protocol1_packet_handler.h"
00023 #elif defined(_WIN32) || defined(_WIN64)
00024 #define WINDLLEXPORT
00025 #include "protocol1_packet_handler.h"
00026 #elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__)
00027 #include "../../include/dynamixel_sdk/protocol1_packet_handler.h"
00028 #endif
00029 
00030 #include <string.h>
00031 #include <stdlib.h>
00032 
00033 #define TXPACKET_MAX_LEN    (250)
00034 #define RXPACKET_MAX_LEN    (250)
00035 
00037 #define PKT_HEADER0             0
00038 #define PKT_HEADER1             1
00039 #define PKT_ID                  2
00040 #define PKT_LENGTH              3
00041 #define PKT_INSTRUCTION         4
00042 #define PKT_ERROR               4
00043 #define PKT_PARAMETER0          5
00044 
00046 #define ERRBIT_VOLTAGE          1       // Supplied voltage is out of the range (operating volatage set in the control table)
00047 #define ERRBIT_ANGLE            2       // Goal position is written out of the range (from CW angle limit to CCW angle limit)
00048 #define ERRBIT_OVERHEAT         4       // Temperature is out of the range (operating temperature set in the control table)
00049 #define ERRBIT_RANGE            8       // Command(setting value) is out of the range for use.
00050 #define ERRBIT_CHECKSUM         16      // Instruction packet checksum is incorrect.
00051 #define ERRBIT_OVERLOAD         32      // The current load cannot be controlled by the set torque.
00052 #define ERRBIT_INSTRUCTION      64      // Undefined instruction or delivering the action command without the reg_write command.
00053 
00054 using namespace dynamixel;
00055 
00056 Protocol1PacketHandler *Protocol1PacketHandler::unique_instance_ = new Protocol1PacketHandler();
00057 
00058 Protocol1PacketHandler::Protocol1PacketHandler() { }
00059 
00060 const char *Protocol1PacketHandler::getTxRxResult(int result)
00061 {
00062   switch(result)
00063   {
00064     case COMM_SUCCESS:
00065       return "[TxRxResult] Communication success.";
00066 
00067     case COMM_PORT_BUSY:
00068       return "[TxRxResult] Port is in use!";
00069 
00070     case COMM_TX_FAIL:
00071       return "[TxRxResult] Failed transmit instruction packet!";
00072 
00073     case COMM_RX_FAIL:
00074       return "[TxRxResult] Failed get status packet from device!";
00075 
00076     case COMM_TX_ERROR:
00077       return "[TxRxResult] Incorrect instruction packet!";
00078 
00079     case COMM_RX_WAITING:
00080       return "[TxRxResult] Now recieving status packet!";
00081 
00082     case COMM_RX_TIMEOUT:
00083       return "[TxRxResult] There is no status packet!";
00084 
00085     case COMM_RX_CORRUPT:
00086       return "[TxRxResult] Incorrect status packet!";
00087 
00088     case COMM_NOT_AVAILABLE:
00089       return "[TxRxResult] Protocol does not support This function!";
00090 
00091     default:
00092       return "";
00093   }
00094 }
00095 
00096 const char *Protocol1PacketHandler::getRxPacketError(uint8_t error)
00097 {
00098   if (error & ERRBIT_VOLTAGE)
00099     return "[RxPacketError] Input voltage error!";
00100 
00101   if (error & ERRBIT_ANGLE)
00102     return "[RxPacketError] Angle limit error!";
00103 
00104   if (error & ERRBIT_OVERHEAT)
00105     return "[RxPacketError] Overheat error!";
00106 
00107   if (error & ERRBIT_RANGE)
00108     return "[RxPacketError] Out of range error!";
00109 
00110   if (error & ERRBIT_CHECKSUM)
00111     return "[RxPacketError] Checksum error!";
00112 
00113   if (error & ERRBIT_OVERLOAD)
00114     return "[RxPacketError] Overload error!";
00115 
00116   if (error & ERRBIT_INSTRUCTION)
00117     return "[RxPacketError] Instruction code error!";
00118 
00119   return "";
00120 }
00121 
00122 int Protocol1PacketHandler::txPacket(PortHandler *port, uint8_t *txpacket)
00123 {
00124   uint8_t checksum               = 0;
00125   uint8_t total_packet_length    = txpacket[PKT_LENGTH] + 4; // 4: HEADER0 HEADER1 ID LENGTH
00126   uint8_t written_packet_length  = 0;
00127 
00128   if (port->is_using_)
00129     return COMM_PORT_BUSY;
00130   port->is_using_ = true;
00131 
00132   // check max packet length
00133   if (total_packet_length > TXPACKET_MAX_LEN)
00134   {
00135     port->is_using_ = false;
00136     return COMM_TX_ERROR;
00137   }
00138 
00139   // make packet header
00140   txpacket[PKT_HEADER0]   = 0xFF;
00141   txpacket[PKT_HEADER1]   = 0xFF;
00142 
00143   // add a checksum to the packet
00144   for (uint16_t idx = 2; idx < total_packet_length - 1; idx++)   // except header, checksum
00145     checksum += txpacket[idx];
00146   txpacket[total_packet_length - 1] = ~checksum;
00147 
00148   // tx packet
00149   port->clearPort();
00150   written_packet_length = port->writePort(txpacket, total_packet_length);
00151   if (total_packet_length != written_packet_length)
00152   {
00153     port->is_using_ = false;
00154     return COMM_TX_FAIL;
00155   }
00156 
00157   return COMM_SUCCESS;
00158 }
00159 
00160 int Protocol1PacketHandler::rxPacket(PortHandler *port, uint8_t *rxpacket)
00161 {
00162   int     result         = COMM_TX_FAIL;
00163 
00164   uint8_t checksum       = 0;
00165   uint8_t rx_length      = 0;
00166   uint8_t wait_length    = 6;    // minimum length (HEADER0 HEADER1 ID LENGTH ERROR CHKSUM)
00167 
00168   while(true)
00169   {
00170     rx_length += port->readPort(&rxpacket[rx_length], wait_length - rx_length);
00171     if (rx_length >= wait_length)
00172     {
00173       uint8_t idx = 0;
00174 
00175       // find packet header
00176       for (idx = 0; idx < (rx_length - 1); idx++)
00177       {
00178         if (rxpacket[idx] == 0xFF && rxpacket[idx+1] == 0xFF)
00179           break;
00180       }
00181 
00182       if (idx == 0)   // found at the beginning of the packet
00183       {
00184         if (rxpacket[PKT_ID] > 0xFD ||                  // unavailable ID
00185             rxpacket[PKT_LENGTH] > RXPACKET_MAX_LEN ||  // unavailable Length
00186             rxpacket[PKT_ERROR] > 0x7F)                 // unavailable Error
00187         {
00188             // remove the first byte in the packet
00189             for (uint16_t s = 0; s < rx_length - 1; s++)
00190               rxpacket[s] = rxpacket[1 + s];
00191             //memcpy(&rxpacket[0], &rxpacket[idx], rx_length - idx);
00192             rx_length -= 1;
00193             continue;
00194         }
00195 
00196         // re-calculate the exact length of the rx packet
00197         if (wait_length != rxpacket[PKT_LENGTH] + PKT_LENGTH + 1)
00198         {
00199           wait_length = rxpacket[PKT_LENGTH] + PKT_LENGTH + 1;
00200           continue;
00201         }
00202 
00203         if (rx_length < wait_length)
00204         {
00205           // check timeout
00206           if (port->isPacketTimeout() == true)
00207           {
00208             if (rx_length == 0)
00209             {
00210               result = COMM_RX_TIMEOUT;
00211             }
00212             else
00213             {
00214               result = COMM_RX_CORRUPT;
00215             }
00216             break;
00217           }
00218           else
00219           {
00220             continue;
00221           }
00222         }
00223 
00224         // calculate checksum
00225         for (uint16_t i = 2; i < wait_length - 1; i++)   // except header, checksum
00226           checksum += rxpacket[i];
00227         checksum = ~checksum;
00228 
00229         // verify checksum
00230         if (rxpacket[wait_length - 1] == checksum)
00231         {
00232           result = COMM_SUCCESS;
00233         }
00234         else
00235         {
00236           result = COMM_RX_CORRUPT;
00237         }
00238         break;
00239       }
00240       else
00241       {
00242         // remove unnecessary packets
00243         for (uint16_t s = 0; s < rx_length - idx; s++)
00244           rxpacket[s] = rxpacket[idx + s];
00245         //memcpy(&rxpacket[0], &rxpacket[idx], rx_length - idx);
00246         rx_length -= idx;
00247       }
00248     }
00249     else
00250     {
00251       // check timeout
00252       if (port->isPacketTimeout() == true)
00253       {
00254         if (rx_length == 0)
00255         {
00256           result = COMM_RX_TIMEOUT;
00257         }
00258         else
00259         {
00260           result = COMM_RX_CORRUPT;
00261         }
00262         break;
00263       }
00264     }
00265   }
00266   port->is_using_ = false;
00267 
00268   return result;
00269 }
00270 
00271 // NOT for BulkRead instruction
00272 int Protocol1PacketHandler::txRxPacket(PortHandler *port, uint8_t *txpacket, uint8_t *rxpacket, uint8_t *error)
00273 {
00274   int result = COMM_TX_FAIL;
00275 
00276   // tx packet
00277   result = txPacket(port, txpacket);
00278   if (result != COMM_SUCCESS)
00279     return result;
00280 
00281   // (Instruction == BulkRead) == this function is not available.
00282   if(txpacket[PKT_INSTRUCTION] == INST_BULK_READ)
00283     result = COMM_NOT_AVAILABLE;
00284 
00285   // (ID == Broadcast ID) == no need to wait for status packet or not available
00286   // (Instruction == action) == no need to wait for status packet
00287   if (txpacket[PKT_ID] == BROADCAST_ID || txpacket[PKT_INSTRUCTION] == INST_ACTION)
00288   {
00289     port->is_using_ = false;
00290     return result;
00291   }
00292 
00293   // set packet timeout
00294   if (txpacket[PKT_INSTRUCTION] == INST_READ)
00295   {
00296     port->setPacketTimeout((uint16_t)(txpacket[PKT_PARAMETER0+1] + 6));
00297   }
00298   else
00299   {
00300     port->setPacketTimeout((uint16_t)6); // HEADER0 HEADER1 ID LENGTH ERROR CHECKSUM
00301   }
00302 
00303   // rx packet
00304   do {
00305     result = rxPacket(port, rxpacket);
00306   } while (result == COMM_SUCCESS && txpacket[PKT_ID] != rxpacket[PKT_ID]);
00307 
00308   if (result == COMM_SUCCESS && txpacket[PKT_ID] == rxpacket[PKT_ID])
00309   {
00310     if (error != 0)
00311       *error = (uint8_t)rxpacket[PKT_ERROR];
00312   }
00313 
00314   return result;
00315 }
00316 
00317 int Protocol1PacketHandler::ping(PortHandler *port, uint8_t id, uint8_t *error)
00318 {
00319   return ping(port, id, 0, error);
00320 }
00321 
00322 int Protocol1PacketHandler::ping(PortHandler *port, uint8_t id, uint16_t *model_number, uint8_t *error)
00323 {
00324   int result                 = COMM_TX_FAIL;
00325 
00326   uint8_t txpacket[6]         = {0};
00327   uint8_t rxpacket[6]         = {0};
00328 
00329   if (id >= BROADCAST_ID)
00330     return COMM_NOT_AVAILABLE;
00331 
00332   txpacket[PKT_ID]            = id;
00333   txpacket[PKT_LENGTH]        = 2;
00334   txpacket[PKT_INSTRUCTION]   = INST_PING;
00335 
00336   result = txRxPacket(port, txpacket, rxpacket, error);
00337   if (result == COMM_SUCCESS && model_number != 0)
00338   {
00339     uint8_t data_read[2] = {0};
00340     result = readTxRx(port, id, 0, 2, data_read);  // Address 0 : Model Number
00341     if (result == COMM_SUCCESS) *model_number = DXL_MAKEWORD(data_read[0], data_read[1]);
00342   }
00343 
00344   return result;
00345 }
00346 
00347 int Protocol1PacketHandler::broadcastPing(PortHandler *port, std::vector<uint8_t> &id_list)
00348 {
00349   return COMM_NOT_AVAILABLE;
00350 }
00351 
00352 int Protocol1PacketHandler::action(PortHandler *port, uint8_t id)
00353 {
00354   uint8_t txpacket[6]         = {0};
00355 
00356   txpacket[PKT_ID]            = id;
00357   txpacket[PKT_LENGTH]        = 2;
00358   txpacket[PKT_INSTRUCTION]   = INST_ACTION;
00359 
00360   return txRxPacket(port, txpacket, 0);
00361 }
00362 
00363 int Protocol1PacketHandler::reboot(PortHandler *port, uint8_t id, uint8_t *error)
00364 {
00365   return COMM_NOT_AVAILABLE;
00366 }
00367 
00368 int Protocol1PacketHandler::factoryReset(PortHandler *port, uint8_t id, uint8_t option, uint8_t *error)
00369 {
00370   uint8_t txpacket[6]         = {0};
00371   uint8_t rxpacket[6]         = {0};
00372 
00373   txpacket[PKT_ID]            = id;
00374   txpacket[PKT_LENGTH]        = 2;
00375   txpacket[PKT_INSTRUCTION]   = INST_FACTORY_RESET;
00376 
00377   return txRxPacket(port, txpacket, rxpacket, error);
00378 }
00379 
00380 int Protocol1PacketHandler::readTx(PortHandler *port, uint8_t id, uint16_t address, uint16_t length)
00381 {
00382   int result                 = COMM_TX_FAIL;
00383 
00384   uint8_t txpacket[8]         = {0};
00385 
00386   if (id >= BROADCAST_ID)
00387     return COMM_NOT_AVAILABLE;
00388 
00389   txpacket[PKT_ID]            = id;
00390   txpacket[PKT_LENGTH]        = 4;
00391   txpacket[PKT_INSTRUCTION]   = INST_READ;
00392   txpacket[PKT_PARAMETER0+0]  = (uint8_t)address;
00393   txpacket[PKT_PARAMETER0+1]  = (uint8_t)length;
00394 
00395   result = txPacket(port, txpacket);
00396 
00397   // set packet timeout
00398   if (result == COMM_SUCCESS)
00399     port->setPacketTimeout((uint16_t)(length+6));
00400 
00401   return result;
00402 }
00403 
00404 int Protocol1PacketHandler::readRx(PortHandler *port, uint8_t id, uint16_t length, uint8_t *data, uint8_t *error)
00405 {
00406   int result                  = COMM_TX_FAIL;
00407   uint8_t *rxpacket           = (uint8_t *)malloc(RXPACKET_MAX_LEN); //(length+6);
00408   //uint8_t *rxpacket         = new uint8_t[length+6];
00409 
00410   do {
00411     result = rxPacket(port, rxpacket);
00412   } while (result == COMM_SUCCESS && rxpacket[PKT_ID] != id);
00413 
00414   if (result == COMM_SUCCESS && rxpacket[PKT_ID] == id)
00415   {
00416     if (error != 0)
00417     {
00418       *error = (uint8_t)rxpacket[PKT_ERROR];
00419     }
00420     for (uint16_t s = 0; s < length; s++)
00421     {
00422       data[s] = rxpacket[PKT_PARAMETER0 + s];
00423     }
00424     //memcpy(data, &rxpacket[PKT_PARAMETER0], length);
00425   }
00426 
00427   free(rxpacket);
00428   //delete[] rxpacket;
00429   return result;
00430 }
00431 
00432 int Protocol1PacketHandler::readTxRx(PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error)
00433 {
00434   int result = COMM_TX_FAIL;
00435 
00436   uint8_t txpacket[8]         = {0};
00437   uint8_t *rxpacket           = (uint8_t *)malloc(RXPACKET_MAX_LEN);//(length+6);
00438 
00439   if (id >= BROADCAST_ID)
00440     return COMM_NOT_AVAILABLE;
00441 
00442   txpacket[PKT_ID]            = id;
00443   txpacket[PKT_LENGTH]        = 4;
00444   txpacket[PKT_INSTRUCTION]   = INST_READ;
00445   txpacket[PKT_PARAMETER0+0]  = (uint8_t)address;
00446   txpacket[PKT_PARAMETER0+1]  = (uint8_t)length;
00447 
00448   result = txRxPacket(port, txpacket, rxpacket, error);
00449   if (result == COMM_SUCCESS)
00450   {
00451     if (error != 0)
00452     {
00453       *error = (uint8_t)rxpacket[PKT_ERROR];
00454     }
00455     for (uint16_t s = 0; s < length; s++)
00456     {
00457       data[s] = rxpacket[PKT_PARAMETER0 + s];
00458     }
00459     //memcpy(data, &rxpacket[PKT_PARAMETER0], length);
00460   }
00461 
00462   free(rxpacket);
00463   //delete[] rxpacket;
00464   return result;
00465 }
00466 
00467 int Protocol1PacketHandler::read1ByteTx(PortHandler *port, uint8_t id, uint16_t address)
00468 {
00469   return readTx(port, id, address, 1);
00470 }
00471 int Protocol1PacketHandler::read1ByteRx(PortHandler *port, uint8_t id, uint8_t *data, uint8_t *error)
00472 {
00473   uint8_t data_read[1] = {0};
00474   int result = readRx(port, id, 1, data_read, error);
00475   if (result == COMM_SUCCESS)
00476     *data = data_read[0];
00477   return result;
00478 }
00479 int Protocol1PacketHandler::read1ByteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint8_t *data, uint8_t *error)
00480 {
00481   uint8_t data_read[1] = {0};
00482   int result = readTxRx(port, id, address, 1, data_read, error);
00483   if (result == COMM_SUCCESS)
00484     *data = data_read[0];
00485   return result;
00486 }
00487 
00488 int Protocol1PacketHandler::read2ByteTx(PortHandler *port, uint8_t id, uint16_t address)
00489 {
00490   return readTx(port, id, address, 2);
00491 }
00492 int Protocol1PacketHandler::read2ByteRx(PortHandler *port, uint8_t id, uint16_t *data, uint8_t *error)
00493 {
00494   uint8_t data_read[2] = {0};
00495   int result = readRx(port, id, 2, data_read, error);
00496   if (result == COMM_SUCCESS)
00497     *data = DXL_MAKEWORD(data_read[0], data_read[1]);
00498   return result;
00499 }
00500 int Protocol1PacketHandler::read2ByteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint16_t *data, uint8_t *error)
00501 {
00502   uint8_t data_read[2] = {0};
00503   int result = readTxRx(port, id, address, 2, data_read, error);
00504   if (result == COMM_SUCCESS)
00505     *data = DXL_MAKEWORD(data_read[0], data_read[1]);
00506   return result;
00507 }
00508 
00509 int Protocol1PacketHandler::read4ByteTx(PortHandler *port, uint8_t id, uint16_t address)
00510 {
00511   return readTx(port, id, address, 4);
00512 }
00513 int Protocol1PacketHandler::read4ByteRx(PortHandler *port, uint8_t id, uint32_t *data, uint8_t *error)
00514 {
00515   uint8_t data_read[4] = {0};
00516   int result = readRx(port, id, 4, data_read, error);
00517   if (result == COMM_SUCCESS)
00518     *data = DXL_MAKEDWORD(DXL_MAKEWORD(data_read[0], data_read[1]), DXL_MAKEWORD(data_read[2], data_read[3]));
00519   return result;
00520 }
00521 int Protocol1PacketHandler::read4ByteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint32_t *data, uint8_t *error)
00522 {
00523   uint8_t data_read[4] = {0};
00524   int result = readTxRx(port, id, address, 4, data_read, error);
00525   if (result == COMM_SUCCESS)
00526     *data = DXL_MAKEDWORD(DXL_MAKEWORD(data_read[0], data_read[1]), DXL_MAKEWORD(data_read[2], data_read[3]));
00527   return result;
00528 }
00529 
00530 int Protocol1PacketHandler::writeTxOnly(PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data)
00531 {
00532   int result                 = COMM_TX_FAIL;
00533 
00534   uint8_t *txpacket           = (uint8_t *)malloc(length+7);
00535   //uint8_t *txpacket           = new uint8_t[length+7];
00536 
00537   txpacket[PKT_ID]            = id;
00538   txpacket[PKT_LENGTH]        = length+3;
00539   txpacket[PKT_INSTRUCTION]   = INST_WRITE;
00540   txpacket[PKT_PARAMETER0]    = (uint8_t)address;
00541 
00542   for (uint16_t s = 0; s < length; s++)
00543     txpacket[PKT_PARAMETER0+1+s] = data[s];
00544   //memcpy(&txpacket[PKT_PARAMETER0+1], data, length);
00545 
00546   result = txPacket(port, txpacket);
00547   port->is_using_ = false;
00548 
00549   free(txpacket);
00550   //delete[] txpacket;
00551   return result;
00552 }
00553 
00554 int Protocol1PacketHandler::writeTxRx(PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error)
00555 {
00556   int result                 = COMM_TX_FAIL;
00557 
00558   uint8_t *txpacket           = (uint8_t *)malloc(length+7); //#6->7
00559   //uint8_t *txpacket           = new uint8_t[length+7];
00560   uint8_t rxpacket[6]         = {0};
00561 
00562   txpacket[PKT_ID]            = id;
00563   txpacket[PKT_LENGTH]        = length+3;
00564   txpacket[PKT_INSTRUCTION]   = INST_WRITE;
00565   txpacket[PKT_PARAMETER0]    = (uint8_t)address;
00566 
00567   for (uint16_t s = 0; s < length; s++)
00568     txpacket[PKT_PARAMETER0+1+s] = data[s];
00569   //memcpy(&txpacket[PKT_PARAMETER0+1], data, length);
00570 
00571   result = txRxPacket(port, txpacket, rxpacket, error);
00572 
00573   free(txpacket);
00574   //delete[] txpacket;
00575   return result;
00576 }
00577 
00578 int Protocol1PacketHandler::write1ByteTxOnly(PortHandler *port, uint8_t id, uint16_t address, uint8_t data)
00579 {
00580   uint8_t data_write[1] = { data };
00581   return writeTxOnly(port, id, address, 1, data_write);
00582 }
00583 int Protocol1PacketHandler::write1ByteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint8_t data, uint8_t *error)
00584 {
00585   uint8_t data_write[1] = { data };
00586   return writeTxRx(port, id, address, 1, data_write, error);
00587 }
00588 
00589 int Protocol1PacketHandler::write2ByteTxOnly(PortHandler *port, uint8_t id, uint16_t address, uint16_t data)
00590 {
00591   uint8_t data_write[2] = { DXL_LOBYTE(data), DXL_HIBYTE(data) };
00592   return writeTxOnly(port, id, address, 2, data_write);
00593 }
00594 int Protocol1PacketHandler::write2ByteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint16_t data, uint8_t *error)
00595 {
00596   uint8_t data_write[2] = { DXL_LOBYTE(data), DXL_HIBYTE(data) };
00597   return writeTxRx(port, id, address, 2, data_write, error);
00598 }
00599 
00600 int Protocol1PacketHandler::write4ByteTxOnly(PortHandler *port, uint8_t id, uint16_t address, uint32_t data)
00601 {
00602   uint8_t data_write[4] = { DXL_LOBYTE(DXL_LOWORD(data)), DXL_HIBYTE(DXL_LOWORD(data)), DXL_LOBYTE(DXL_HIWORD(data)), DXL_HIBYTE(DXL_HIWORD(data)) };
00603   return writeTxOnly(port, id, address, 4, data_write);
00604 }
00605 int Protocol1PacketHandler::write4ByteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint32_t data, uint8_t *error)
00606 {
00607   uint8_t data_write[4] = { DXL_LOBYTE(DXL_LOWORD(data)), DXL_HIBYTE(DXL_LOWORD(data)), DXL_LOBYTE(DXL_HIWORD(data)), DXL_HIBYTE(DXL_HIWORD(data)) };
00608   return writeTxRx(port, id, address, 4, data_write, error);
00609 }
00610 
00611 int Protocol1PacketHandler::regWriteTxOnly(PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data)
00612 {
00613   int result                 = COMM_TX_FAIL;
00614 
00615   uint8_t *txpacket           = (uint8_t *)malloc(length+6);
00616   //uint8_t *txpacket           = new uint8_t[length+6];
00617 
00618   txpacket[PKT_ID]            = id;
00619   txpacket[PKT_LENGTH]        = length+3;
00620   txpacket[PKT_INSTRUCTION]   = INST_REG_WRITE;
00621   txpacket[PKT_PARAMETER0]    = (uint8_t)address;
00622 
00623   for (uint16_t s = 0; s < length; s++)
00624     txpacket[PKT_PARAMETER0+1+s] = data[s];
00625   //memcpy(&txpacket[PKT_PARAMETER0+1], data, length);
00626 
00627   result = txPacket(port, txpacket);
00628   port->is_using_ = false;
00629 
00630   free(txpacket);
00631   //delete[] txpacket;
00632   return result;
00633 }
00634 
00635 int Protocol1PacketHandler::regWriteTxRx(PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error)
00636 {
00637   int result                 = COMM_TX_FAIL;
00638 
00639   uint8_t *txpacket           = (uint8_t *)malloc(length+6);
00640   //uint8_t *txpacket           = new uint8_t[length+6];
00641   uint8_t rxpacket[6]         = {0};
00642 
00643   txpacket[PKT_ID]            = id;
00644   txpacket[PKT_LENGTH]        = length+3;
00645   txpacket[PKT_INSTRUCTION]   = INST_REG_WRITE;
00646   txpacket[PKT_PARAMETER0]    = (uint8_t)address;
00647 
00648   for (uint16_t s = 0; s < length; s++)
00649     txpacket[PKT_PARAMETER0+1+s] = data[s];
00650   //memcpy(&txpacket[PKT_PARAMETER0+1], data, length);
00651 
00652   result = txRxPacket(port, txpacket, rxpacket, error);
00653 
00654   free(txpacket);
00655   //delete[] txpacket;
00656   return result;
00657 }
00658 
00659 int Protocol1PacketHandler::syncReadTx(PortHandler *port, uint16_t start_address, uint16_t data_length, uint8_t *param, uint16_t param_length)
00660 {
00661   return COMM_NOT_AVAILABLE;
00662 }
00663 
00664 int Protocol1PacketHandler::syncWriteTxOnly(PortHandler *port, uint16_t start_address, uint16_t data_length, uint8_t *param, uint16_t param_length)
00665 {
00666   int result                 = COMM_TX_FAIL;
00667 
00668   uint8_t *txpacket           = (uint8_t *)malloc(param_length+8);
00669   // 8: HEADER0 HEADER1 ID LEN INST START_ADDR DATA_LEN ... CHKSUM
00670   //uint8_t *txpacket           = new uint8_t[param_length + 8];
00671 
00672   txpacket[PKT_ID]            = BROADCAST_ID;
00673   txpacket[PKT_LENGTH]        = param_length + 4; // 4: INST START_ADDR DATA_LEN ... CHKSUM
00674   txpacket[PKT_INSTRUCTION]   = INST_SYNC_WRITE;
00675   txpacket[PKT_PARAMETER0+0]  = start_address;
00676   txpacket[PKT_PARAMETER0+1]  = data_length;
00677 
00678   for (uint16_t s = 0; s < param_length; s++)
00679     txpacket[PKT_PARAMETER0+2+s] = param[s];
00680   //memcpy(&txpacket[PKT_PARAMETER0+2], param, param_length);
00681 
00682   result = txRxPacket(port, txpacket, 0, 0);
00683 
00684   free(txpacket);
00685   //delete[] txpacket;
00686   return result;
00687 }
00688 
00689 int Protocol1PacketHandler::bulkReadTx(PortHandler *port, uint8_t *param, uint16_t param_length)
00690 {
00691   int result                 = COMM_TX_FAIL;
00692 
00693   uint8_t *txpacket           = (uint8_t *)malloc(param_length+7);
00694   // 7: HEADER0 HEADER1 ID LEN INST 0x00 ... CHKSUM
00695   //uint8_t *txpacket           = new uint8_t[param_length + 7];
00696 
00697   txpacket[PKT_ID]            = BROADCAST_ID;
00698   txpacket[PKT_LENGTH]        = param_length + 3; // 3: INST 0x00 ... CHKSUM
00699   txpacket[PKT_INSTRUCTION]   = INST_BULK_READ;
00700   txpacket[PKT_PARAMETER0+0]  = 0x00;
00701 
00702   for (uint16_t s = 0; s < param_length; s++)
00703     txpacket[PKT_PARAMETER0+1+s] = param[s];
00704   //memcpy(&txpacket[PKT_PARAMETER0+1], param, param_length);
00705 
00706   result = txPacket(port, txpacket);
00707   if (result == COMM_SUCCESS)
00708   {
00709     int wait_length = 0;
00710     for (uint16_t i = 0; i < param_length; i += 3)
00711       wait_length += param[i] + 7;
00712     port->setPacketTimeout((uint16_t)wait_length);
00713   }
00714 
00715   free(txpacket);
00716   //delete[] txpacket;
00717   return result;
00718 }
00719 
00720 int Protocol1PacketHandler::bulkWriteTxOnly(PortHandler *port, uint8_t *param, uint16_t param_length)
00721 {
00722   return COMM_NOT_AVAILABLE;
00723 }


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