-
Notifications
You must be signed in to change notification settings - Fork 64
Expand file tree
/
Copy pathping.ino
More file actions
122 lines (107 loc) · 4.77 KB
/
ping.ino
File metadata and controls
122 lines (107 loc) · 4.77 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
/*******************************************************************************
* Copyright 2016 ROBOTIS CO., LTD.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*******************************************************************************/
#include <Dynamixel2Arduino.h>
// Please modify it to suit your hardware.
#if defined(ARDUINO_AVR_UNO) || defined(ARDUINO_AVR_MEGA2560) // When using DynamixelShield
#include <SoftwareSerial.h>
SoftwareSerial soft_serial(7, 8); // DYNAMIXELShield UART RX/TX
#define DXL_SERIAL Serial
#define DEBUG_SERIAL soft_serial
const int DXL_DIR_PIN = 2; // DYNAMIXEL Shield DIR PIN
#elif defined(ARDUINO_SAM_DUE) // When using DynamixelShield
#define DXL_SERIAL Serial
#define DEBUG_SERIAL SerialUSB
const int DXL_DIR_PIN = 2; // DYNAMIXEL Shield DIR PIN
#elif defined(ARDUINO_SAM_ZERO) // When using DynamixelShield
#define DXL_SERIAL Serial1
#define DEBUG_SERIAL SerialUSB
const int DXL_DIR_PIN = 2; // DYNAMIXEL Shield DIR PIN
#elif defined(ARDUINO_OpenCM904) // When using official ROBOTIS board with DXL circuit.
#define DXL_SERIAL Serial3 //OpenCM9.04 EXP Board's DXL port Serial. (Serial1 for the DXL port on the OpenCM 9.04 board)
#define DEBUG_SERIAL Serial
const int DXL_DIR_PIN = 22; //OpenCM9.04 EXP Board's DIR PIN. (28 for the DXL port on the OpenCM 9.04 board)
#elif defined(ARDUINO_OpenCR) // When using official ROBOTIS board with DXL circuit.
// For OpenCR, there is a DXL Power Enable pin, so you must initialize and control it.
// Reference link : https://github.com/ROBOTIS-GIT/OpenCR/blob/master/arduino/opencr_arduino/opencr/libraries/DynamixelSDK/src/dynamixel_sdk/port_handler_arduino.cpp#L78
#define DXL_SERIAL Serial3
#define DEBUG_SERIAL Serial
const int DXL_DIR_PIN = 84; // OpenCR Board's DIR PIN.
#elif defined(ARDUINO_OpenRB) // When using OpenRB-150
//OpenRB does not require the DIR control pin.
#define DXL_SERIAL Serial1
#define DEBUG_SERIAL Serial
const int DXL_DIR_PIN = -1;
#else // Other boards when using DynamixelShield
#define DXL_SERIAL Serial1
#define DEBUG_SERIAL Serial
const int DXL_DIR_PIN = 2; // DYNAMIXEL Shield DIR PIN
#endif
const uint8_t DXL_ID = 1;
// MX and AX servos use DYNAMIXEL Protocol 1.0 by default.
// to use MX and AX servos with this example, change the following line to: const float DXL_PROTOCOL_VERSION = 1.0;
const float DXL_PROTOCOL_VERSION = 2.0;
Dynamixel2Arduino dxl(DXL_SERIAL, DXL_DIR_PIN);
//This namespace is required to use Control table item names
using namespace ControlTableItem;
void setup() {
// put your setup code here, to run once:
// Use Serial to debug.
DEBUG_SERIAL.begin(115200);
// Set Port baudrate to 57600bps. This has to match with DYNAMIXEL baudrate.
dxl.begin(57600);
// Set Port Protocol Version. This has to match with DYNAMIXEL protocol version.
dxl.setPortProtocolVersion(DXL_PROTOCOL_VERSION);
}
void loop() {
// put your main code here, to run repeatedly:
DEBUG_SERIAL.print("PROTOCOL ");
DEBUG_SERIAL.print(DXL_PROTOCOL_VERSION, 1);
DEBUG_SERIAL.print(", ID ");
DEBUG_SERIAL.print(DXL_ID);
DEBUG_SERIAL.print(": ");
if(dxl.ping(DXL_ID) == true){
DEBUG_SERIAL.print("ping succeeded!");
DEBUG_SERIAL.print(", Model Number: ");
DEBUG_SERIAL.println(dxl.getModelNumber(DXL_ID));
}else{
DEBUG_SERIAL.print("ping failed!, err code: ");
DEBUG_SERIAL.println(dxl.getLastLibErrCode());
}
delay(500);
FindServos();
}
DYNAMIXEL::InfoFromPing_t ping_info[32];
void FindServos(void) {
Serial.println(" Try Protocol 2 - broadcast ping: ");
Serial.flush(); // flush it as ping may take awhile...
if (uint8_t count_pinged = dxl.ping(DXL_BROADCAST_ID, ping_info,
sizeof(ping_info)/sizeof(ping_info[0]))) {
Serial.print("Detected Dynamixel : \n");
for (int i = 0; i < count_pinged; i++)
{
Serial.print(" ");
Serial.print(ping_info[i].id, DEC);
Serial.print(", Model:");
Serial.print(ping_info[i].model_number);
Serial.print(", Ver:");
Serial.println(ping_info[i].firmware_version, DEC);
//g_servo_protocol[i] = 2;
}
}else{
Serial.print("Broadcast returned no items : ");
Serial.println(dxl.getLastLibErrCode());
}
}