group_bulk_write.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 "group_bulk_write.h"
23 #elif defined(__APPLE__)
24 #include "group_bulk_write.h"
25 #elif defined(_WIN32) || defined(_WIN64)
26 #define WINDLLEXPORT
27 #include "group_bulk_write.h"
28 #elif defined(ARDUINO) || defined(__OPENCR__) || defined(__OPENCM904__)
29 #include "../../include/dynamixel_sdk/group_bulk_write.h"
30 #endif
31 
32 using namespace dynamixel;
33 
35  : port_(port),
36  ph_(ph),
37  is_param_changed_(false),
38  param_(0),
39  param_length_(0)
40 {
41  clearParam();
42 }
43 
45 {
46  if (ph_->getProtocolVersion() == 1.0 || id_list_.size() == 0)
47  return;
48 
49  if (param_ != 0)
50  delete[] param_;
51  param_ = 0;
52 
53  param_length_ = 0;
54  for (unsigned int i = 0; i < id_list_.size(); i++)
55  param_length_ += 1 + 2 + 2 + length_list_[id_list_[i]];
56 
57  param_ = new uint8_t[param_length_];
58 
59  int idx = 0;
60  for (unsigned int i = 0; i < id_list_.size(); i++)
61  {
62  uint8_t id = id_list_[i];
63  if (data_list_[id] == 0)
64  return;
65 
66  param_[idx++] = id;
67  param_[idx++] = DXL_LOBYTE(address_list_[id]);
68  param_[idx++] = DXL_HIBYTE(address_list_[id]);
69  param_[idx++] = DXL_LOBYTE(length_list_[id]);
70  param_[idx++] = DXL_HIBYTE(length_list_[id]);
71  for (int c = 0; c < length_list_[id]; c++)
72  param_[idx++] = (data_list_[id])[c];
73  }
74 }
75 
76 bool GroupBulkWrite::addParam(uint8_t id, uint16_t start_address, uint16_t data_length, uint8_t *data)
77 {
78  if (ph_->getProtocolVersion() == 1.0)
79  return false;
80 
81  if (std::find(id_list_.begin(), id_list_.end(), id) != id_list_.end()) // id already exist
82  return false;
83 
84  id_list_.push_back(id);
85  address_list_[id] = start_address;
86  length_list_[id] = data_length;
87  data_list_[id] = new uint8_t[data_length];
88  for (int c = 0; c < data_length; c++)
89  data_list_[id][c] = data[c];
90 
91  is_param_changed_ = true;
92  return true;
93 }
95 {
96  if (ph_->getProtocolVersion() == 1.0)
97  return;
98 
99  std::vector<uint8_t>::iterator it = std::find(id_list_.begin(), id_list_.end(), id);
100  if (it == id_list_.end()) // NOT exist
101  return;
102 
103  id_list_.erase(it);
104  address_list_.erase(id);
105  length_list_.erase(id);
106  delete[] data_list_[id];
107  data_list_.erase(id);
108 
109  is_param_changed_ = true;
110 }
111 bool GroupBulkWrite::changeParam(uint8_t id, uint16_t start_address, uint16_t data_length, uint8_t *data)
112 {
113  if (ph_->getProtocolVersion() == 1.0)
114  return false;
115 
116  std::vector<uint8_t>::iterator it = std::find(id_list_.begin(), id_list_.end(), id);
117  if (it == id_list_.end()) // NOT exist
118  return false;
119 
120  address_list_[id] = start_address;
121  length_list_[id] = data_length;
122  delete[] data_list_[id];
123  data_list_[id] = new uint8_t[data_length];
124  for (int c = 0; c < data_length; c++)
125  data_list_[id][c] = data[c];
126 
127  is_param_changed_ = true;
128  return true;
129 }
131 {
132  if (ph_->getProtocolVersion() == 1.0 || id_list_.size() == 0)
133  return;
134 
135  for (unsigned int i = 0; i < id_list_.size(); i++)
136  delete[] data_list_[id_list_[i]];
137 
138  id_list_.clear();
139  address_list_.clear();
140  length_list_.clear();
141  data_list_.clear();
142  if (param_ != 0)
143  delete[] param_;
144  param_ = 0;
145 }
147 {
148  if (ph_->getProtocolVersion() == 1.0 || id_list_.size() == 0)
149  return COMM_NOT_AVAILABLE;
150 
151  if (is_param_changed_ == true || param_ == 0)
152  makeParam();
153 
155 }
GroupBulkWrite(PortHandler *port, PacketHandler *ph)
The function that Initializes instance for Bulk Write.
std::map< uint8_t, uint16_t > length_list_
std::vector< uint8_t > id_list_
bool changeParam(uint8_t id, uint16_t start_address, uint16_t data_length, uint8_t *data)
The function that changes the data for write in id -> start_address -> data_length to the Bulk Write ...
int txPacket()
The function that transmits the Bulk Write instruction packet which might be constructed by GroupBulk...
void removeParam(uint8_t id)
The function that removes id from the Bulk Write list.
virtual int bulkWriteTxOnly(PortHandler *port, uint8_t *param, uint16_t param_length)=0
The function that transmits INST_BULK_WRITE instruction packet The function makes an instruction pac...
The class that inherits Protocol1PacketHandler class or Protocol2PacketHandler class.
void clearParam()
The function that clears the Bulk Write list.
#define DXL_LOBYTE(w)
The class for port control that inherits PortHandlerLinux, PortHandlerWindows, PortHandlerMac, or PortHandlerArduino.
Definition: port_handler.h:56
virtual float getProtocolVersion()=0
The function that returns Protocol version.
#define DXL_HIBYTE(w)
std::map< uint8_t, uint8_t * > data_list_
#define COMM_NOT_AVAILABLE
std::map< uint8_t, uint16_t > address_list_
bool addParam(uint8_t id, uint16_t start_address, uint16_t data_length, uint8_t *data)
The function that adds id, start_address, data_length to the Bulk Write list.


dynamixel_sdk
Author(s): Gilbert , Zerom , Darby Lim , Leon
autogenerated on Fri Apr 16 2021 02:25:55