dynamixel_driver.h
Go to the documentation of this file.
1 /*******************************************************************************
2 * Copyright 2018 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 /* Authors: Taehun Lim (Darby) */
18 
19 #ifndef DYNAMIXEL_DRIVER_H
20 #define DYNAMIXEL_DRIVER_H
21 
22 #include "dynamixel_tool.h"
23 
24 #if defined(__OPENCR__) || defined(__OPENCM904__)
25  #include <Arduino.h>
26  #include <DynamixelSDK.h>
27 #elif defined(__linux__) || defined(__APPLE__)
28  #include "unistd.h"
30 #endif
31 
32 #define MAX_DXL_SERIES_NUM 5
33 #define MAX_HANDLER_NUM 5
34 #define MAX_BULK_PARAMETER 20
35 
36 typedef struct
37 {
41 
42 typedef struct
43 {
47 
48 typedef struct
49 {
50  uint8_t id;
51  uint16_t address;
52  uint16_t data_length;
54 
55 typedef struct
56 {
60  uint8_t dxl_error;
61 } ErrorFromSDK;
62 
64 {
65  private:
68 
71 
75 
77 
78  uint8_t tools_cnt_;
82 
83  public:
86 
87  bool init(const char* device_name = "/dev/ttyUSB0",
88  uint32_t baud_rate = 57600,
89  const char **log = NULL);
90 
91  bool begin(const char* device_name = "/dev/ttyUSB0",
92  uint32_t baud_rate = 57600,
93  const char **log = NULL);
94 
95  bool setPortHandler(const char *device_name, const char **log = NULL);
96  bool setBaudrate(uint32_t baud_rate, const char **log = NULL);
97  bool setPacketHandler(float protocol_version, const char **log = NULL);
98 
99  float getProtocolVersion(void);
100  uint32_t getBaudrate(void);
101 
102  const char * getModelName(uint8_t id, const char **log = NULL);
103  uint16_t getModelNumber(uint8_t id, const char **log = NULL);
104  const ControlItem *getControlTable(uint8_t id, const char **log = NULL);
105  const ControlItem *getItemInfo(uint8_t id, const char *item_name, const char **log = NULL);
106  uint8_t getTheNumberOfControlItem(uint8_t id, const char **log = NULL);
107  const ModelInfo* getModelInfo(uint8_t id, const char **log = NULL);
108 
109  uint8_t getTheNumberOfSyncWriteHandler(void);
110  uint8_t getTheNumberOfSyncReadHandler(void);
111  uint8_t getTheNumberOfBulkReadParam(void);
112 
113  bool scan(uint8_t *get_id,
114  uint8_t *get_the_number_of_id,
115  uint8_t range = 253,
116  const char **log = NULL);
117 
118  bool scan(uint8_t *get_id,
119  uint8_t *get_the_number_of_id,
120  uint8_t start_number,
121  uint8_t end_number,
122  const char **log = NULL);
123 
124  bool ping(uint8_t id,
125  uint16_t *get_model_number,
126  const char **log = NULL);
127 
128  bool ping(uint8_t id,
129  const char **log = NULL);
130 
131  bool clearMultiTurn(uint8_t id, const char **log = NULL);
132 
133  bool reboot(uint8_t id, const char **log = NULL);
134  bool reset(uint8_t id, const char **log = NULL);
135 
136  bool writeRegister(uint8_t id, uint16_t address, uint16_t length, uint8_t* data, const char **log = NULL);
137  bool writeRegister(uint8_t id, const char *item_name, int32_t data, const char **log = NULL);
138 
139  bool writeOnlyRegister(uint8_t id, uint16_t address, uint16_t length, uint8_t *data, const char **log = NULL);
140  bool writeOnlyRegister(uint8_t id, const char *item_name, int32_t data, const char **log = NULL);
141 
142  bool readRegister(uint8_t id, uint16_t address, uint16_t length, uint32_t *data, const char **log = NULL);
143  bool readRegister(uint8_t id, const char *item_name, int32_t *data, const char **log = NULL);
144 
145  void getParam(int32_t data, uint8_t *param);
146 
147  bool addSyncWriteHandler(uint16_t address, uint16_t length, const char **log = NULL);
148  bool addSyncWriteHandler(uint8_t id, const char *item_name, const char **log = NULL);
149 
150  bool syncWrite(uint8_t index, int32_t *data, const char **log = NULL);
151  bool syncWrite(uint8_t index, uint8_t *id, uint8_t id_num, int32_t *data, uint8_t data_num_for_each_id, const char **log = NULL);
152 
153  bool addSyncReadHandler(uint16_t address, uint16_t length, const char **log = NULL);
154  bool addSyncReadHandler(uint8_t id, const char *item_name, const char **log = NULL);
155 
156  bool syncRead(uint8_t index, const char **log = NULL);
157  bool syncRead(uint8_t index, uint8_t *id, uint8_t id_num, const char **log = NULL);
158 
159  bool getSyncReadData(uint8_t index, int32_t *data, const char **log = NULL);
160  bool getSyncReadData(uint8_t index, uint8_t *id, uint8_t id_num, int32_t *data, const char **log = NULL);
161  bool getSyncReadData(uint8_t index, uint8_t *id, uint8_t id_num, uint16_t address, uint16_t length, int32_t *data, const char **log = NULL);
162 
163  bool initBulkWrite(const char **log = NULL);
164 
165  bool addBulkWriteParam(uint8_t id, uint16_t address, uint16_t length, int32_t data, const char **log = NULL);
166  bool addBulkWriteParam(uint8_t id, const char *item_name, int32_t data, const char **log = NULL);
167 
168  bool bulkWrite(const char **log = NULL);
169 
170  bool initBulkRead(const char **log = NULL);
171 
172  bool addBulkReadParam(uint8_t id, uint16_t address, uint16_t length, const char **log = NULL);
173  bool addBulkReadParam(uint8_t id, const char *item_name, const char **log = NULL);
174 
175  bool bulkRead(const char **log = NULL);
176 
177  bool getBulkReadData(int32_t *data, const char **log = NULL);
178  bool getBulkReadData(uint8_t *id, uint8_t id_num, uint16_t *address, uint16_t *length, int32_t *data, const char **log = NULL);
179 
180  bool clearBulkReadParam(void);
181 
182  private:
183  void initTools(void);
184  bool setTool(uint16_t model_number, uint8_t id, const char **log = NULL);
185  uint8_t getTool(uint8_t id, const char **log = NULL);
186 };
187 
188 #endif //DYNAMIXEL_DRIVER_H
SyncWriteHandler syncWriteHandler_[MAX_HANDLER_NUM]
uint32_t getBaudrate(void)
bool addBulkWriteParam(uint8_t id, uint16_t address, uint16_t length, int32_t data, const char **log=NULL)
bool addBulkReadParam(uint8_t id, uint16_t address, uint16_t length, const char **log=NULL)
dynamixel::GroupBulkRead * groupBulkRead_
const ControlItem * control_item
bool getBulkReadData(int32_t *data, const char **log=NULL)
uint8_t getTheNumberOfSyncWriteHandler(void)
#define MAX_BULK_PARAMETER
dynamixel::GroupSyncWrite * groupSyncWrite
bool setPacketHandler(float protocol_version, const char **log=NULL)
bool init(const char *device_name="/dev/ttyUSB0", uint32_t baud_rate=57600, const char **log=NULL)
dynamixel::PacketHandler * packetHandler_
const ControlItem * control_item
bool syncWrite(uint8_t index, int32_t *data, const char **log=NULL)
bool readRegister(uint8_t id, uint16_t address, uint16_t length, uint32_t *data, const char **log=NULL)
const char * getModelName(uint8_t id, const char **log=NULL)
bool writeRegister(uint8_t id, uint16_t address, uint16_t length, uint8_t *data, const char **log=NULL)
bool clearMultiTurn(uint8_t id, const char **log=NULL)
bool reset(uint8_t id, const char **log=NULL)
SyncReadHandler syncReadHandler_[MAX_HANDLER_NUM]
bool writeOnlyRegister(uint8_t id, uint16_t address, uint16_t length, uint8_t *data, const char **log=NULL)
bool addSyncWriteHandler(uint16_t address, uint16_t length, const char **log=NULL)
bool addSyncReadHandler(uint16_t address, uint16_t length, const char **log=NULL)
bool begin(const char *device_name="/dev/ttyUSB0", uint32_t baud_rate=57600, const char **log=NULL)
uint8_t sync_write_handler_cnt_
const ControlItem * getItemInfo(uint8_t id, const char *item_name, const char **log=NULL)
bool ping(uint8_t id, uint16_t *get_model_number, const char **log=NULL)
bool scan(uint8_t *get_id, uint8_t *get_the_number_of_id, uint8_t range=253, const char **log=NULL)
bool getSyncReadData(uint8_t index, int32_t *data, const char **log=NULL)
DynamixelTool tools_[MAX_DXL_SERIES_NUM]
uint8_t bulk_read_parameter_cnt_
uint8_t getTheNumberOfSyncReadHandler(void)
dynamixel::PortHandler * portHandler_
bool initBulkWrite(const char **log=NULL)
bool clearBulkReadParam(void)
uint16_t data_length
const ModelInfo * getModelInfo(uint8_t id, const char **log=NULL)
dynamixel::GroupBulkWrite * groupBulkWrite_
bool setPortHandler(const char *device_name, const char **log=NULL)
bool initBulkRead(const char **log=NULL)
uint8_t getTheNumberOfBulkReadParam(void)
dynamixel::GroupSyncRead * groupSyncRead
#define MAX_DXL_SERIES_NUM
bool bulkWrite(const char **log=NULL)
const ControlItem * getControlTable(uint8_t id, const char **log=NULL)
bool reboot(uint8_t id, const char **log=NULL)
uint8_t getTheNumberOfControlItem(uint8_t id, const char **log=NULL)
bool bulkRead(const char **log=NULL)
void getParam(int32_t data, uint8_t *param)
bool setTool(uint16_t model_number, uint8_t id, const char **log=NULL)
uint8_t getTool(uint8_t id, const char **log=NULL)
bool syncRead(uint8_t index, const char **log=NULL)
uint8_t get_id[16]
Definition: p_Monitor.cpp:30
uint16_t getModelNumber(uint8_t id, const char **log=NULL)
uint8_t sync_read_handler_cnt_
float getProtocolVersion(void)
#define MAX_HANDLER_NUM
bool setBaudrate(uint32_t baud_rate, const char **log=NULL)
BulkParameter bulk_read_param_[MAX_BULK_PARAMETER]
bool dxl_addparam_result


dynamixel_workbench_toolbox
Author(s): Darby Lim , Ryan Shim
autogenerated on Mon Sep 28 2020 03:37:05