|
| 1 | +/******************************************************************************* |
| 2 | +* Copyright 2022 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 | +// Tutorial Video: https://youtu.be/msWlMyx8Nrw |
| 18 | +// Example Environment |
| 19 | +// |
| 20 | +// - DYNAMIXEL: X series |
| 21 | +// ID = 1, Baudrate = 57600bps, DYNAMIXEL Protocol 2.0 |
| 22 | +// - Controller: Arduino MKR ZERO |
| 23 | +// DYNAMIXEL Shield for Arduino MKR |
| 24 | +// - https://emanual.robotis.com/docs/en/parts/interface/mkr_shield/ |
| 25 | +// - Adjust the position_p_gain, position_i_gain, position_d_gain values |
| 26 | +// Author: David Park |
| 27 | + |
| 28 | +#include <Dynamixel2Arduino.h> |
| 29 | + |
| 30 | +// Please modify it to suit your hardware. |
| 31 | +#if defined(ARDUINO_AVR_UNO) || defined(ARDUINO_AVR_MEGA2560) // When using DynamixelShield |
| 32 | + #include <SoftwareSerial.h> |
| 33 | + SoftwareSerial soft_serial(7, 8); // DYNAMIXELShield UART RX/TX |
| 34 | + #define DXL_SERIAL Serial |
| 35 | + #define DEBUG_SERIAL soft_serial |
| 36 | + const uint8_t DXL_DIR_PIN = 2; // DYNAMIXEL Shield DIR PIN |
| 37 | +#elif defined(ARDUINO_SAM_DUE) // When using DynamixelShield |
| 38 | + #define DXL_SERIAL Serial |
| 39 | + #define DEBUG_SERIAL SerialUSB |
| 40 | + const uint8_t DXL_DIR_PIN = 2; // DYNAMIXEL Shield DIR PIN |
| 41 | +#elif defined(ARDUINO_SAM_ZERO) // When using DynamixelShield |
| 42 | + #define DXL_SERIAL Serial1 |
| 43 | + #define DEBUG_SERIAL SerialUSB |
| 44 | + const uint8_t DXL_DIR_PIN = 2; // DYNAMIXEL Shield DIR PIN |
| 45 | +#elif defined(ARDUINO_OpenCM904) // When using official ROBOTIS board with DXL circuit. |
| 46 | + #define DXL_SERIAL Serial3 //OpenCM9.04 EXP Board's DXL port Serial. (Serial1 for the DXL port on the OpenCM 9.04 board) |
| 47 | + #define DEBUG_SERIAL Serial |
| 48 | + const uint8_t DXL_DIR_PIN = 22; //OpenCM9.04 EXP Board's DIR PIN. (28 for the DXL port on the OpenCM 9.04 board) |
| 49 | +#elif defined(ARDUINO_OpenCR) // When using official ROBOTIS board with DXL circuit. |
| 50 | + // For OpenCR, there is a DXL Power Enable pin, so you must initialize and control it. |
| 51 | + // Reference link : https://github.com/ROBOTIS-GIT/OpenCR/blob/master/arduino/opencr_arduino/opencr/libraries/DynamixelSDK/src/dynamixel_sdk/port_handler_arduino.cpp#L78 |
| 52 | + #define DXL_SERIAL Serial3 |
| 53 | + #define DEBUG_SERIAL Serial |
| 54 | + const uint8_t DXL_DIR_PIN = 84; // OpenCR Board's DIR PIN. |
| 55 | +#else // Other boards when using DynamixelShield |
| 56 | + #define DXL_SERIAL Serial1 |
| 57 | + #define DEBUG_SERIAL Serial |
| 58 | + const uint8_t DXL_DIR_PIN = 2; // DYNAMIXEL Shield DIR PIN |
| 59 | +#endif |
| 60 | + |
| 61 | +const uint8_t DXL_ID = 1; |
| 62 | +const uint32_t DXL_BAUDRATE = 57600; |
| 63 | +const float DXL_PROTOCOL_VERSION = 2.0; |
| 64 | + |
| 65 | +int32_t goal_position[2] = {1200, 1600}; |
| 66 | +int8_t direction = 0; |
| 67 | +unsigned long timer = 0; |
| 68 | + |
| 69 | +// Position PID Gains |
| 70 | +// Adjust these gains to tune the behavior of DYNAMIXEL |
| 71 | +uint16_t position_p_gain = 0; |
| 72 | +uint16_t position_i_gain = 0; |
| 73 | +uint16_t position_d_gain = 0; |
| 74 | + |
| 75 | +Dynamixel2Arduino dxl(DXL_SERIAL, DXL_DIR_PIN); |
| 76 | + |
| 77 | +//This namespace is required to use Control table item names |
| 78 | +using namespace ControlTableItem; |
| 79 | + |
| 80 | +void setup() { |
| 81 | + // put your setup code here, to run once: |
| 82 | + // For Uno, Nano, Mini, and Mega, use the UART port of the DYNAMIXEL Shield to read debugging messages. |
| 83 | + DEBUG_SERIAL.begin(57600); |
| 84 | + while(!DEBUG_SERIAL); |
| 85 | + |
| 86 | + // Set Port baudrate to 57600bps. This has to match with DYNAMIXEL baudrate. |
| 87 | + dxl.begin(DXL_BAUDRATE); |
| 88 | + // Set Port Protocol Version. This has to match with DYNAMIXEL protocol version. |
| 89 | + dxl.setPortProtocolVersion(DXL_PROTOCOL_VERSION); |
| 90 | + // Get DYNAMIXEL information |
| 91 | + dxl.ping(DXL_ID); |
| 92 | + |
| 93 | + // Turn off torque when configuring items in EEPROM area |
| 94 | + dxl.torqueOff(DXL_ID); |
| 95 | + dxl.setOperatingMode(DXL_ID, OP_POSITION); |
| 96 | + dxl.torqueOn(DXL_ID); |
| 97 | + |
| 98 | + // Set Position PID Gains |
| 99 | + dxl.writeControlTableItem(POSITION_P_GAIN, DXL_ID, position_p_gain); |
| 100 | + dxl.writeControlTableItem(POSITION_I_GAIN, DXL_ID, position_i_gain); |
| 101 | + dxl.writeControlTableItem(POSITION_D_GAIN, DXL_ID, position_d_gain); |
| 102 | +} |
| 103 | + |
| 104 | +void loop() { |
| 105 | + // put your main code here, to run repeatedly: |
| 106 | + // Read Present Position (Use the Serial Plotter) |
| 107 | + while(true) { |
| 108 | + DEBUG_SERIAL.print("Goal_Position:"); |
| 109 | + DEBUG_SERIAL.print(dxl.readControlTableItem(GOAL_POSITION, DXL_ID)); |
| 110 | + DEBUG_SERIAL.print(","); |
| 111 | + DEBUG_SERIAL.print("Present_Position:"); |
| 112 | + DEBUG_SERIAL.print(dxl.getPresentPosition(DXL_ID)); |
| 113 | + DEBUG_SERIAL.print(","); |
| 114 | + DEBUG_SERIAL.println(); |
| 115 | + delay(10); |
| 116 | + |
| 117 | + if (millis() - timer >= 2000) { |
| 118 | + dxl.setGoalPosition(DXL_ID, goal_position[direction]); |
| 119 | + timer = millis(); |
| 120 | + break; |
| 121 | + } |
| 122 | + } |
| 123 | + |
| 124 | + if(direction >= 1) { |
| 125 | + direction = 0; |
| 126 | + } else { |
| 127 | + direction = 1; |
| 128 | + } |
| 129 | +} |
0 commit comments