o_Find_Dynamixel.cpp
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 #include <DynamixelWorkbench.h>
20 
21 #define BAUDRATE_NUM 7
22 
23 int main(int argc, char *argv[])
24 {
25  const char* port_name = "/dev/ttyUSB0";
26 
27  if (argc < 2)
28  {
29  printf("Please set '-port_name' arguments for connected Dynamixels\n");
30  return 0;
31  }
32  else
33  {
34  port_name = argv[1];
35  }
36 
38 
39  const char *log;
40  bool result = false;
41 
42  uint8_t scanned_id[100];
43  uint8_t dxl_cnt = 0;
44 
45  uint32_t baudrate[BAUDRATE_NUM] = {9600, 57600, 115200, 1000000, 2000000, 3000000, 4000000};
46  uint8_t range = 253;
47 
48  uint8_t index = 0;
49 
50  while (index < BAUDRATE_NUM)
51  {
52  result = dxl_wb.init(port_name, baudrate[index], &log);
53  if (result == false)
54  {
55  printf("%s\n", log);
56  printf("Failed to init\n");
57  }
58  else
59  printf("Succeed to init(%d)\n", baudrate[index]);
60 
61  dxl_cnt = 0;
62  for (uint8_t num = 0; num < 100; num++) scanned_id[num] = 0;
63 
64  printf("Wait for scan...\n");
65  result = dxl_wb.scan(scanned_id, &dxl_cnt, range, &log);
66  if (result == false)
67  {
68  printf("%s\n", log);
69  printf("Failed to scan\n");
70  }
71  else
72  {
73  printf("Find %d Dynamixels\n", dxl_cnt);
74 
75  for (int cnt = 0; cnt < dxl_cnt; cnt++)
76  printf("id : %d, model name : %s\n", scanned_id[cnt], dxl_wb.getModelName(scanned_id[cnt]));
77  }
78 
79  index++;
80  }
81 
82  return 0;
83 }
bool init(const char *device_name="/dev/ttyUSB0", uint32_t baud_rate=57600, const char **log=NULL)
#define BAUDRATE_NUM
DynamixelWorkbench dxl_wb
Definition: p_Monitor.cpp:40
const char * getModelName(uint8_t id, 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)
int main(int argc, char *argv[])


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