Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019 #include <stdio.h>
00020 #include <algorithm>
00021
00022 #if defined(__linux__)
00023 #include "group_bulk_read.h"
00024 #elif defined(__APPLE__)
00025 #include "group_bulk_read.h"
00026 #elif defined(_WIN32) || defined(_WIN64)
00027 #define WINDLLEXPORT
00028 #include "group_bulk_read.h"
00029 #elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__)
00030 #include "../../include/dynamixel_sdk/group_bulk_read.h"
00031 #endif
00032
00033 using namespace dynamixel;
00034
00035 GroupBulkRead::GroupBulkRead(PortHandler *port, PacketHandler *ph)
00036 : port_(port),
00037 ph_(ph),
00038 last_result_(false),
00039 is_param_changed_(false),
00040 param_(0)
00041 {
00042 clearParam();
00043 }
00044
00045 void GroupBulkRead::makeParam()
00046 {
00047 if (id_list_.size() == 0)
00048 return;
00049
00050 if (param_ != 0)
00051 delete[] param_;
00052 param_ = 0;
00053
00054 if (ph_->getProtocolVersion() == 1.0)
00055 {
00056 param_ = new uint8_t[id_list_.size() * 3];
00057 }
00058 else
00059 {
00060 param_ = new uint8_t[id_list_.size() * 5];
00061 }
00062
00063 int idx = 0;
00064 for (unsigned int i = 0; i < id_list_.size(); i++)
00065 {
00066 uint8_t id = id_list_[i];
00067 if (ph_->getProtocolVersion() == 1.0)
00068 {
00069 param_[idx++] = (uint8_t)length_list_[id];
00070 param_[idx++] = id;
00071 param_[idx++] = (uint8_t)address_list_[id];
00072 }
00073 else
00074 {
00075 param_[idx++] = id;
00076 param_[idx++] = DXL_LOBYTE(address_list_[id]);
00077 param_[idx++] = DXL_HIBYTE(address_list_[id]);
00078 param_[idx++] = DXL_LOBYTE(length_list_[id]);
00079 param_[idx++] = DXL_HIBYTE(length_list_[id]);
00080 }
00081 }
00082 }
00083
00084 bool GroupBulkRead::addParam(uint8_t id, uint16_t start_address, uint16_t data_length)
00085 {
00086 if (std::find(id_list_.begin(), id_list_.end(), id) != id_list_.end())
00087 return false;
00088
00089 id_list_.push_back(id);
00090 length_list_[id] = data_length;
00091 address_list_[id] = start_address;
00092 data_list_[id] = new uint8_t[data_length];
00093 error_list_[id] = new uint8_t[1];
00094
00095 is_param_changed_ = true;
00096 return true;
00097 }
00098
00099 void GroupBulkRead::removeParam(uint8_t id)
00100 {
00101 std::vector<uint8_t>::iterator it = std::find(id_list_.begin(), id_list_.end(), id);
00102 if (it == id_list_.end())
00103 return;
00104
00105 id_list_.erase(it);
00106 address_list_.erase(id);
00107 length_list_.erase(id);
00108 delete[] data_list_[id];
00109 delete[] error_list_[id];
00110 data_list_.erase(id);
00111 error_list_.erase(id);
00112
00113 is_param_changed_ = true;
00114 }
00115
00116 void GroupBulkRead::clearParam()
00117 {
00118 if (id_list_.size() == 0)
00119 return;
00120
00121 for (unsigned int i = 0; i < id_list_.size(); i++)
00122 {
00123 delete[] data_list_[id_list_[i]];
00124 delete[] error_list_[id_list_[i]];
00125 }
00126
00127 id_list_.clear();
00128 address_list_.clear();
00129 length_list_.clear();
00130 data_list_.clear();
00131 error_list_.clear();
00132 if (param_ != 0)
00133 delete[] param_;
00134 param_ = 0;
00135 }
00136
00137 int GroupBulkRead::txPacket()
00138 {
00139 if (id_list_.size() == 0)
00140 return COMM_NOT_AVAILABLE;
00141
00142 if (is_param_changed_ == true || param_ == 0)
00143 makeParam();
00144
00145 if (ph_->getProtocolVersion() == 1.0)
00146 {
00147 return ph_->bulkReadTx(port_, param_, id_list_.size() * 3);
00148 }
00149 else
00150 {
00151 return ph_->bulkReadTx(port_, param_, id_list_.size() * 5);
00152 }
00153 }
00154
00155 int GroupBulkRead::rxPacket()
00156 {
00157 int cnt = id_list_.size();
00158 int result = COMM_RX_FAIL;
00159
00160 last_result_ = false;
00161
00162 if (cnt == 0)
00163 return COMM_NOT_AVAILABLE;
00164
00165 for (int i = 0; i < cnt; i++)
00166 {
00167 uint8_t id = id_list_[i];
00168
00169 result = ph_->readRx(port_, id, length_list_[id], data_list_[id], error_list_[id]);
00170 if (result != COMM_SUCCESS)
00171 return result;
00172 }
00173
00174 if (result == COMM_SUCCESS)
00175 last_result_ = true;
00176
00177 return result;
00178 }
00179
00180 int GroupBulkRead::txRxPacket()
00181 {
00182 int result = COMM_TX_FAIL;
00183
00184 result = txPacket();
00185 if (result != COMM_SUCCESS)
00186 return result;
00187
00188 return rxPacket();
00189 }
00190
00191 bool GroupBulkRead::isAvailable(uint8_t id, uint16_t address, uint16_t data_length)
00192 {
00193 uint16_t start_addr;
00194
00195 if (last_result_ == false || data_list_.find(id) == data_list_.end())
00196 return false;
00197
00198 start_addr = address_list_[id];
00199
00200 if (address < start_addr || start_addr + length_list_[id] - data_length < address)
00201 return false;
00202
00203 return true;
00204 }
00205
00206 uint32_t GroupBulkRead::getData(uint8_t id, uint16_t address, uint16_t data_length)
00207 {
00208 if (isAvailable(id, address, data_length) == false)
00209 return 0;
00210
00211 uint16_t start_addr = address_list_[id];
00212
00213 switch(data_length)
00214 {
00215 case 1:
00216 return data_list_[id][address - start_addr];
00217
00218 case 2:
00219 return DXL_MAKEWORD(data_list_[id][address - start_addr], data_list_[id][address - start_addr + 1]);
00220
00221 case 4:
00222 return DXL_MAKEDWORD(DXL_MAKEWORD(data_list_[id][address - start_addr + 0], data_list_[id][address - start_addr + 1]),
00223 DXL_MAKEWORD(data_list_[id][address - start_addr + 2], data_list_[id][address - start_addr + 3]));
00224
00225 default:
00226 return 0;
00227 }
00228 }
00229
00230 bool GroupBulkRead::getError(uint8_t id, uint8_t* error)
00231 {
00232
00233
00234
00235 error[0] = error_list_[id][0];
00236
00237 if (error[0] != 0)
00238 {
00239 return true;
00240 }
00241 else
00242 {
00243 return false;
00244 }
00245 }