group_sync_read.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 #include <algorithm>
00020 
00021 #if defined(__linux__)
00022 #include "group_sync_read.h"
00023 #elif defined(__APPLE__)
00024 #include "group_sync_read.h"
00025 #elif defined(_WIN32) || defined(_WIN64)
00026 #define WINDLLEXPORT
00027 #include "group_sync_read.h"
00028 #elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__)
00029 #include "../../include/dynamixel_sdk/group_sync_read.h"
00030 #endif
00031 
00032 using namespace dynamixel;
00033 
00034 GroupSyncRead::GroupSyncRead(PortHandler *port, PacketHandler *ph, uint16_t start_address, uint16_t data_length)
00035   : port_(port),
00036     ph_(ph),
00037     last_result_(false),
00038     is_param_changed_(false),
00039     param_(0),
00040     start_address_(start_address),
00041     data_length_(data_length)
00042 {
00043   clearParam();
00044 }
00045 
00046 void GroupSyncRead::makeParam()
00047 {
00048   if (ph_->getProtocolVersion() == 1.0 || id_list_.size() == 0)
00049     return;
00050 
00051   if (param_ != 0)
00052     delete[] param_;
00053   param_ = 0;
00054 
00055   param_ = new uint8_t[id_list_.size() * 1];  // ID(1)
00056 
00057   int idx = 0;
00058   for (unsigned int i = 0; i < id_list_.size(); i++)
00059     param_[idx++] = id_list_[i];
00060 }
00061 
00062 bool GroupSyncRead::addParam(uint8_t id)
00063 {
00064   if (ph_->getProtocolVersion() == 1.0)
00065     return false;
00066 
00067   if (std::find(id_list_.begin(), id_list_.end(), id) != id_list_.end())   // id already exist
00068     return false;
00069 
00070   id_list_.push_back(id);
00071   data_list_[id] = new uint8_t[data_length_];
00072   error_list_[id] = new uint8_t[1];
00073 
00074   is_param_changed_   = true;
00075   return true;
00076 }
00077 void GroupSyncRead::removeParam(uint8_t id)
00078 {
00079   if (ph_->getProtocolVersion() == 1.0)
00080     return;
00081 
00082   std::vector<uint8_t>::iterator it = std::find(id_list_.begin(), id_list_.end(), id);
00083   if (it == id_list_.end())    // NOT exist
00084     return;
00085 
00086   id_list_.erase(it);
00087   delete[] data_list_[id];
00088   delete[] error_list_[id];
00089   data_list_.erase(id);
00090   error_list_.erase(id);
00091 
00092   is_param_changed_   = true;
00093 }
00094 void GroupSyncRead::clearParam()
00095 {
00096   if (ph_->getProtocolVersion() == 1.0 || id_list_.size() == 0)
00097     return;
00098 
00099   for (unsigned int i = 0; i < id_list_.size(); i++)
00100   {
00101     delete[] data_list_[id_list_[i]];
00102     delete[] error_list_[id_list_[i]];
00103   }
00104 
00105   id_list_.clear();
00106   data_list_.clear();
00107   error_list_.clear();
00108   if (param_ != 0)
00109     delete[] param_;
00110   param_ = 0;
00111 }
00112 
00113 int GroupSyncRead::txPacket()
00114 {
00115   if (ph_->getProtocolVersion() == 1.0 || id_list_.size() == 0)
00116     return COMM_NOT_AVAILABLE;
00117 
00118   if (is_param_changed_ == true || param_ == 0)
00119     makeParam();
00120 
00121   return ph_->syncReadTx(port_, start_address_, data_length_, param_, (uint16_t)id_list_.size() * 1);
00122 }
00123 
00124 int GroupSyncRead::rxPacket()
00125 {
00126   last_result_ = false;
00127 
00128   if (ph_->getProtocolVersion() == 1.0)
00129     return COMM_NOT_AVAILABLE;
00130 
00131   int cnt            = id_list_.size();
00132   int result         = COMM_RX_FAIL;
00133 
00134   if (cnt == 0)
00135     return COMM_NOT_AVAILABLE;
00136 
00137   for (int i = 0; i < cnt; i++)
00138   {
00139     uint8_t id = id_list_[i];
00140 
00141     result = ph_->readRx(port_, id, data_length_, data_list_[id], error_list_[id]);
00142     if (result != COMM_SUCCESS)
00143       return result;
00144   }
00145 
00146   if (result == COMM_SUCCESS)
00147     last_result_ = true;
00148 
00149   return result;
00150 }
00151 
00152 int GroupSyncRead::txRxPacket()
00153 {
00154   if (ph_->getProtocolVersion() == 1.0)
00155     return COMM_NOT_AVAILABLE;
00156 
00157   int result         = COMM_TX_FAIL;
00158 
00159   result = txPacket();
00160   if (result != COMM_SUCCESS)
00161     return result;
00162 
00163   return rxPacket();
00164 }
00165 
00166 bool GroupSyncRead::isAvailable(uint8_t id, uint16_t address, uint16_t data_length)
00167 {
00168   if (ph_->getProtocolVersion() == 1.0 || last_result_ == false || data_list_.find(id) == data_list_.end())
00169     return false;
00170 
00171   if (address < start_address_ || start_address_ + data_length_ - data_length < address)
00172     return false;
00173 
00174   return true;
00175 }
00176 
00177 uint32_t GroupSyncRead::getData(uint8_t id, uint16_t address, uint16_t data_length)
00178 {
00179   if (isAvailable(id, address, data_length) == false)
00180     return 0;
00181 
00182   switch(data_length)
00183   {
00184     case 1:
00185       return data_list_[id][address - start_address_];
00186 
00187     case 2:
00188       return DXL_MAKEWORD(data_list_[id][address - start_address_], data_list_[id][address - start_address_ + 1]);
00189 
00190     case 4:
00191       return DXL_MAKEDWORD(DXL_MAKEWORD(data_list_[id][address - start_address_ + 0], data_list_[id][address - start_address_ + 1]),
00192                  DXL_MAKEWORD(data_list_[id][address - start_address_ + 2], data_list_[id][address - start_address_ + 3]));
00193 
00194     default:
00195       return 0;
00196   }
00197 }
00198 
00199 bool GroupSyncRead::getError(uint8_t id, uint8_t* error)
00200 {
00201   // TODO : check protocol version, last_result_, data_list
00202   // if (ph_->getProtocolVersion() == 1.0 || last_result_ == false || error_list_.find(id) == error_list_.end())
00203 
00204   error[0] = error_list_[id][0];
00205 
00206   if (error[0] != 0)
00207   {
00208     return true;
00209   }
00210   else
00211   {
00212     return false;
00213   }
00214 }


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