group_sync_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_GROUPSYNCWRITE_H_
23 #define DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_GROUPSYNCWRITE_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 GroupSyncWrite
38 {
39  private:
42 
43  std::vector<uint8_t> id_list_;
44  std::map<uint8_t, uint8_t* > data_list_; // <id, data>
45 
47 
48  uint8_t *param_;
49  uint16_t start_address_;
50  uint16_t data_length_;
51 
52  void makeParam();
53 
54  public:
62  GroupSyncWrite(PortHandler *port, PacketHandler *ph, uint16_t start_address, uint16_t data_length);
63 
67  ~GroupSyncWrite() { clearParam(); }
68 
73  PortHandler *getPortHandler() { return port_; }
74 
79  PacketHandler *getPacketHandler() { return ph_; }
80 
89  bool addParam (uint8_t id, uint8_t *data);
90 
95  void removeParam (uint8_t id);
96 
105  bool changeParam (uint8_t id, uint8_t *data);
106 
110  void clearParam ();
111 
118  int txPacket();
119 };
120 
121 }
122 
123 
124 #endif /* DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_GROUPSYNCWRITE_H_ */
PortHandler * getPortHandler()
The function that returns PortHandler instance.
std::map< uint8_t, uint8_t * > data_list_
PacketHandler * getPacketHandler()
The function that returns PacketHandler instance.
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
~GroupSyncWrite()
The function that calls clearParam function to clear the parameter list for Sync Write.
The class for writing multiple Dynamixel data from same address with same length at once...
std::vector< uint8_t > id_list_


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