group_bulk_write.h
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 
21 
22 #ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_GROUPBULKWRITE_H_
23 #define DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_GROUPBULKWRITE_H_
24 
25 
26 #include <map>
27 #include <vector>
28 #include "port_handler.h"
29 #include "packet_handler.h"
30 
31 namespace dynamixel
32 {
33 
37 class WINDECLSPEC GroupBulkWrite
38 {
39  private:
42 
43  std::vector<uint8_t> id_list_;
44  std::map<uint8_t, uint16_t> address_list_; // <id, start_address>
45  std::map<uint8_t, uint16_t> length_list_; // <id, data_length>
46  std::map<uint8_t, uint8_t *> data_list_; // <id, data>
47 
49 
50  uint8_t *param_;
51  uint16_t param_length_;
52 
53  void makeParam();
54 
55  public:
62 
66  ~GroupBulkWrite() { clearParam(); }
67 
72  PortHandler *getPortHandler() { return port_; }
73 
78  PacketHandler *getPacketHandler() { return ph_; }
79 
89  bool addParam (uint8_t id, uint16_t start_address, uint16_t data_length, uint8_t *data);
90 
95  void removeParam (uint8_t id);
96 
107  bool changeParam (uint8_t id, uint16_t start_address, uint16_t data_length, uint8_t *data);
108 
112  void clearParam ();
113 
121  int txPacket();
122 };
123 
124 }
125 
126 
127 #endif /* DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_GROUPBULKWRITE_H_ */
The class for writing multiple Dynamixel data from different addresses with different lengths at once...
std::map< uint8_t, uint16_t > length_list_
PacketHandler * getPacketHandler()
The function that returns PacketHandler instance.
std::vector< uint8_t > id_list_
~GroupBulkWrite()
The function that calls clearParam function to clear the parameter list for Bulk Write.
The class that inherits Protocol1PacketHandler class or Protocol2PacketHandler class.
The class for port control that inherits PortHandlerLinux, PortHandlerWindows, PortHandlerMac, or PortHandlerArduino.
Definition: port_handler.h:56
std::map< uint8_t, uint8_t * > data_list_
PortHandler * getPortHandler()
The function that returns PortHandler instance.
std::map< uint8_t, uint16_t > address_list_


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