MercurySDK
Software development kit for Mercury digital servos
group_sync_read.cpp
Go to the documentation of this file.
1 /*******************************************************************************
2 * Copyright 2017 ROBOTIS CO., LTD.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License");
5 * you may not use this file except in compliance with the License.
6 * You may obtain a copy of the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS,
12 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 * See the License for the specific language governing permissions and
14 * limitations under the License.
15 *******************************************************************************/
16 
17 /* Author: zerom, Ryu Woon Jung (Leon) */
18 
19 #include <algorithm>
20 
21 #if defined(__linux__)
22 #include "../../include/mercury_sdk/group_sync_read.h"
23 #elif defined(__APPLE__)
24 #include "group_sync_read.h"
25 #elif defined(_WIN32) || defined(_WIN64)
26 #define WINDLLEXPORT
27 #include "group_sync_read.h"
28 #elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__) || defined(ARDUINO_OpenRB)
29 #include "../../include/mercury_sdk/group_sync_read.h"
30 #endif
31 
32 using namespace mercury;
33 
34 GroupSyncRead::GroupSyncRead(PortHandler *port, PacketHandler *ph, uint16_t start_address, uint16_t data_length)
35  : GroupHandler(port, ph),
36  last_result_(false),
37  start_address_(start_address),
38  data_length_(data_length)
39 {
40  clearParam();
41 }
42 
44 {
45  if (ph_->getProtocolVersion() == 1.0 || id_list_.size() == 0)
46  return;
47 
48  if (param_ != 0)
49  delete[] param_;
50  param_ = 0;
51 
52  param_ = new uint8_t[id_list_.size() * 1]; // ID(1)
53 
54  int idx = 0;
55  for (unsigned int i = 0; i < id_list_.size(); i++)
56  param_[idx++] = id_list_[i];
57 }
58 
59 bool GroupSyncRead::addParam(uint8_t id)
60 {
61  if (ph_->getProtocolVersion() == 1.0)
62  return false;
63 
64  if (std::find(id_list_.begin(), id_list_.end(), id) != id_list_.end()) // id already exist
65  return false;
66 
67  id_list_.push_back(id);
68  data_list_[id] = new uint8_t[data_length_];
69  error_list_[id] = new uint8_t[1];
70 
71  is_param_changed_ = true;
72  return true;
73 }
75 {
76  if (ph_->getProtocolVersion() == 1.0)
77  return;
78 
79  std::vector<uint8_t>::iterator it = std::find(id_list_.begin(), id_list_.end(), id);
80  if (it == id_list_.end()) // NOT exist
81  return;
82 
83  id_list_.erase(it);
84  delete[] data_list_[id];
85  delete[] error_list_[id];
86  data_list_.erase(id);
87  error_list_.erase(id);
88 
89  is_param_changed_ = true;
90 }
92 {
93  if (ph_->getProtocolVersion() == 1.0 || id_list_.size() == 0)
94  return;
95 
96  for (unsigned int i = 0; i < id_list_.size(); i++)
97  {
98  delete[] data_list_[id_list_[i]];
99  delete[] error_list_[id_list_[i]];
100  }
101 
102  id_list_.clear();
103  data_list_.clear();
104  error_list_.clear();
105  if (param_ != 0)
106  delete[] param_;
107  param_ = 0;
108 }
109 
111 {
112  if (ph_->getProtocolVersion() == 1.0 || id_list_.size() == 0)
113  return COMM_NOT_AVAILABLE;
114 
115  if (is_param_changed_ == true || param_ == 0)
116  makeParam();
117 
118  return ph_->syncReadTx(port_, start_address_, data_length_, param_, (uint16_t)id_list_.size() * 1);
119 }
120 
122 {
123  last_result_ = false;
124 
125  if (ph_->getProtocolVersion() == 1.0)
126  return COMM_NOT_AVAILABLE;
127 
128  int cnt = id_list_.size();
129  int result = COMM_RX_FAIL;
130 
131  if (cnt == 0)
132  return COMM_NOT_AVAILABLE;
133 
134  for (int i = 0; i < cnt; i++)
135  {
136  uint8_t id = id_list_[i];
137 
138  result = ph_->readRx(port_, id, data_length_, data_list_[id], error_list_[id]);
139  if (result != COMM_SUCCESS)
140  return result;
141  }
142 
143  if (result == COMM_SUCCESS)
144  last_result_ = true;
145 
146  return result;
147 }
148 
150 {
151  if (ph_->getProtocolVersion() == 1.0)
152  return COMM_NOT_AVAILABLE;
153 
154  int result = COMM_TX_FAIL;
155 
156  result = txPacket();
157  if (result != COMM_SUCCESS)
158  return result;
159 
160  return rxPacket();
161 }
162 
163 bool GroupSyncRead::isAvailable(uint8_t id, uint16_t address, uint16_t data_length)
164 {
165  if (ph_->getProtocolVersion() == 1.0 || last_result_ == false || data_list_.find(id) == data_list_.end())
166  return false;
167 
168  if (address < start_address_ || start_address_ + data_length_ - data_length < address)
169  return false;
170 
171  return true;
172 }
173 
174 uint32_t GroupSyncRead::getData(uint8_t id, uint16_t address, uint16_t data_length)
175 {
176  if (isAvailable(id, address, data_length) == false)
177  return 0;
178 
179  switch(data_length)
180  {
181  case 1:
182  return data_list_[id][address - start_address_];
183 
184  case 2:
185  return MCY_MAKEWORD(data_list_[id][address - start_address_], data_list_[id][address - start_address_ + 1]);
186 
187  case 4:
188  return MCY_MAKEDWORD(MCY_MAKEWORD(data_list_[id][address - start_address_ + 0], data_list_[id][address - start_address_ + 1]),
189  MCY_MAKEWORD(data_list_[id][address - start_address_ + 2], data_list_[id][address - start_address_ + 3]));
190 
191  default:
192  return 0;
193  }
194 }
195 
196 bool GroupSyncRead::getError(uint8_t id, uint8_t* error)
197 {
198  return error[0] = error_list_[id][0];
199 }
PacketHandler * ph_
Definition: group_handler.h:44
std::vector< uint8_t > id_list_
Definition: group_handler.h:46
std::map< uint8_t, uint8_t * > data_list_
Definition: group_handler.h:47
PortHandler * port_
Definition: group_handler.h:43
std::map< uint8_t, uint8_t * > error_list_
bool addParam(uint8_t id)
The function that adds id, start_address, data_length to the Sync Read list.
int txPacket()
The function that transmits the Sync Read instruction packet which might be constructed by GroupSyncR...
int txRxPacket()
The function that transmits and receives the packet which might be come from the Dynamixel.
bool getError(uint8_t id, uint8_t *error)
The function that gets the error which might be received by GroupSyncRead::rxPacket or GroupSyncRead:...
bool isAvailable(uint8_t id, uint16_t address, uint16_t data_length)
The function that checks whether there are available data which might be received by GroupSyncRead::r...
uint32_t getData(uint8_t id, uint16_t address, uint16_t data_length)
The function that gets the data which might be received by GroupSyncRead::rxPacket or GroupSyncRead::...
GroupSyncRead(PortHandler *port, PacketHandler *ph, uint16_t start_address, uint16_t data_length)
The function that Initializes instance for Sync Read.
void clearParam()
The function that clears the Sync Read list.
int rxPacket()
The function that receives the packet which might be come from the Dynamixel.
void removeParam(uint8_t id)
The function that removes id from the Sync Read list.
The class that inherits Protocol1PacketHandler class or Protocol2PacketHandler class.
virtual int readRx(PortHandler *port, uint8_t id, uint16_t length, uint8_t *data, uint8_t *error=0)=0
The function that receives the packet and reads the data in the packet @description The function rece...
virtual float getProtocolVersion()=0
The function that returns Protocol version.
virtual int syncReadTx(PortHandler *port, uint16_t start_address, uint16_t data_length, uint8_t *param, uint16_t param_length)=0
The function that transmits INST_SYNC_READ instruction packet @description The function makes an inst...
The class for port control that inherits PortHandlerLinux, PortHandlerWindows, PortHandlerMac,...
Definition: port_handler.h:56
#define COMM_RX_FAIL
#define MCY_MAKEDWORD(a, b)
#define COMM_NOT_AVAILABLE
#define COMM_SUCCESS
#define MCY_MAKEWORD(a, b)
#define COMM_TX_FAIL