group_sync_read.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_GROUPSYNCREAD_H_
23 #define DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_GROUPSYNCREAD_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 GroupSyncRead
38 {
39  private:
42 
43  std::vector<uint8_t> id_list_;
44  std::map<uint8_t, uint8_t *> data_list_; // <id, data>
45  std::map<uint8_t, uint8_t *> error_list_; // <id, error>
46 
49 
50  uint8_t *param_;
51  uint16_t start_address_;
52  uint16_t data_length_;
53 
54  void makeParam();
55 
56  public:
64  GroupSyncRead(PortHandler *port, PacketHandler *ph, uint16_t start_address, uint16_t data_length);
65 
69  ~GroupSyncRead() { clearParam(); }
70 
75  PortHandler *getPortHandler() { return port_; }
76 
81  PacketHandler *getPacketHandler() { return ph_; }
82 
91  bool addParam (uint8_t id);
92 
97  void removeParam (uint8_t id);
98 
102  void clearParam ();
103 
111  int txPacket();
112 
122  int rxPacket();
123 
134  int txRxPacket();
135 
146  bool isAvailable (uint8_t id, uint16_t address, uint16_t data_length);
147 
155  uint32_t getData (uint8_t id, uint16_t address, uint16_t data_length);
156 
165  bool getError (uint8_t id, uint8_t* error);
166 };
167 
168 }
169 
170 
171 #endif /* DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_GROUPSYNCREAD_H_ */
std::map< uint8_t, uint8_t * > data_list_
PacketHandler * getPacketHandler()
The function that returns PacketHandler instance.
~GroupSyncRead()
The function that calls clearParam function to clear the parameter list for Sync Read.
The class for reading multiple Dynamixel data from same address with same length at once...
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::vector< uint8_t > id_list_
std::map< uint8_t, uint8_t * > error_list_
PortHandler * getPortHandler()
The function that returns PortHandler instance.


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