|
| 1 | +/******************************************************************************* |
| 2 | +* Copyright 2016 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 | +#include <Dynamixel2Arduino.h> |
| 18 | + |
| 19 | +// Please modify it to suit your hardware. |
| 20 | +#if defined(ARDUINO_AVR_UNO) || defined(ARDUINO_AVR_MEGA2560) // When using DynamixelShield |
| 21 | + #include <SoftwareSerial.h> |
| 22 | + SoftwareSerial soft_serial(7, 8); // DYNAMIXELShield UART RX/TX |
| 23 | + #define DXL_SERIAL Serial |
| 24 | + #define DEBUG_SERIAL soft_serial |
| 25 | + const uint8_t DXL_DIR_PIN = 2; // DYNAMIXEL Shield DIR PIN |
| 26 | +#elif defined(ARDUINO_SAM_DUE) // When using DynamixelShield |
| 27 | + #define DXL_SERIAL Serial |
| 28 | + #define DEBUG_SERIAL SerialUSB |
| 29 | + const uint8_t DXL_DIR_PIN = 2; // DYNAMIXEL Shield DIR PIN |
| 30 | +#elif defined(ARDUINO_SAM_ZERO) // When using DynamixelShield |
| 31 | + #define DXL_SERIAL Serial1 |
| 32 | + #define DEBUG_SERIAL SerialUSB |
| 33 | + const uint8_t DXL_DIR_PIN = 2; // DYNAMIXEL Shield DIR PIN |
| 34 | +#elif defined(ARDUINO_OpenCM904) // When using official ROBOTIS board with DXL circuit. |
| 35 | + #define DXL_SERIAL Serial3 //OpenCM9.04 EXP Board's DXL port Serial. (Serial1 for the DXL port on the OpenCM 9.04 board) |
| 36 | + #define DEBUG_SERIAL Serial |
| 37 | + 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) |
| 38 | +#elif defined(ARDUINO_OpenCR) // When using official ROBOTIS board with DXL circuit. |
| 39 | + // For OpenCR, there is a DXL Power Enable pin, so you must initialize and control it. |
| 40 | + // Reference link : https://github.com/ROBOTIS-GIT/OpenCR/blob/master/arduino/opencr_arduino/opencr/libraries/DynamixelSDK/src/dynamixel_sdk/port_handler_arduino.cpp#L78 |
| 41 | + #define DXL_SERIAL Serial3 |
| 42 | + #define DEBUG_SERIAL Serial |
| 43 | + const uint8_t DXL_DIR_PIN = 84; // OpenCR Board's DIR PIN. |
| 44 | +#else // Other boards when using DynamixelShield |
| 45 | + #define DXL_SERIAL Serial1 |
| 46 | + #define DEBUG_SERIAL Serial |
| 47 | + const uint8_t DXL_DIR_PIN = 2; // DYNAMIXEL Shield DIR PIN |
| 48 | +#endif |
| 49 | + |
| 50 | + |
| 51 | +/* syncRead |
| 52 | + Structures containing the necessary information to process the 'syncRead' packet. |
| 53 | +
|
| 54 | + typedef struct XELInfoBulkRead{ |
| 55 | + uint16_t addr; |
| 56 | + uint16_t addr_length; |
| 57 | + uint8_t *p_recv_buf; |
| 58 | + uint8_t id; |
| 59 | + uint8_t error; |
| 60 | + } __attribute__((packed)) XELInfoBulkRead_t; |
| 61 | +
|
| 62 | + typedef struct InfoBulkReadInst{ |
| 63 | + XELInfoBulkRead_t* p_xels; |
| 64 | + uint8_t xel_count; |
| 65 | + bool is_info_changed; |
| 66 | + InfoSyncBulkBuffer_t packet; |
| 67 | + } __attribute__((packed)) InfoBulkReadInst_t; |
| 68 | +*/ |
| 69 | + |
| 70 | +/* syncWrite |
| 71 | + Structures containing the necessary information to process the 'syncWrite' packet. |
| 72 | +
|
| 73 | + typedef struct XELInfoBulkWrite{ |
| 74 | + uint16_t addr; |
| 75 | + uint16_t addr_length; |
| 76 | + uint8_t* p_data; |
| 77 | + uint8_t id; |
| 78 | + } __attribute__((packed)) XELInfoBulkWrite_t; |
| 79 | +
|
| 80 | + typedef struct InfoBulkWriteInst{ |
| 81 | + XELInfoBulkWrite_t* p_xels; |
| 82 | + uint8_t xel_count; |
| 83 | + bool is_info_changed; |
| 84 | + InfoSyncBulkBuffer_t packet; |
| 85 | + } __attribute__((packed)) InfoBulkWriteInst_t; |
| 86 | +*/ |
| 87 | + |
| 88 | +const uint8_t BROADCAST_ID = 254; |
| 89 | +const float DYNAMIXEL_PROTOCOL_VERSION = 2.0; |
| 90 | +const uint8_t DXL_ID_CNT = 2; |
| 91 | +const uint8_t DXL_ID_LIST[DXL_ID_CNT] = {1, 2}; |
| 92 | +const uint16_t user_pkt_buf_cap = 128; |
| 93 | +uint8_t user_pkt_buf[user_pkt_buf_cap]; |
| 94 | + |
| 95 | +const uint16_t SR_START_ADDR = 132; // Starting Data Addr, Can differ Depending on what address to access |
| 96 | +const uint16_t SR_ADDR_LEN = 4; // Data Length, Can differ depending on how many address to access. |
| 97 | +const uint16_t SW_START_ADDR = 116; |
| 98 | +const uint16_t SW_ADDR_LEN = 4; |
| 99 | +typedef struct sr_data{ |
| 100 | + int32_t present_position; |
| 101 | +} __attribute__((packed)) sr_data_t; |
| 102 | +typedef struct sw_data{ |
| 103 | + int32_t goal_position; |
| 104 | +} __attribute__((packed)) sw_data_t; |
| 105 | + |
| 106 | + |
| 107 | +sr_data_t sr_data[DXL_ID_CNT]; |
| 108 | +DYNAMIXEL::InfoSyncReadInst_t sr_infos; |
| 109 | +DYNAMIXEL::XELInfoSyncRead_t info_xels_sr[DXL_ID_CNT]; |
| 110 | + |
| 111 | +sw_data_t sw_data[DXL_ID_CNT]; |
| 112 | +DYNAMIXEL::InfoSyncWriteInst_t sw_infos; |
| 113 | +DYNAMIXEL::XELInfoSyncWrite_t info_xels_sw[DXL_ID_CNT]; |
| 114 | + |
| 115 | +Dynamixel2Arduino dxl(DXL_SERIAL, DXL_DIR_PIN); |
| 116 | + |
| 117 | +//This namespace is required to use Control table item names |
| 118 | +using namespace ControlTableItem; |
| 119 | + |
| 120 | +int32_t goal_position[2] = {1024, 2048}; |
| 121 | +uint8_t direction = 0; |
| 122 | + |
| 123 | +void setup() { |
| 124 | + // put your setup code here, to run once: |
| 125 | + uint8_t i; |
| 126 | + pinMode(LED_BUILTIN, OUTPUT); |
| 127 | + DEBUG_SERIAL.begin(115200); |
| 128 | + dxl.begin(57600); |
| 129 | + dxl.setPortProtocolVersion(DYNAMIXEL_PROTOCOL_VERSION); |
| 130 | + |
| 131 | + for(i=0; i<DXL_ID_CNT; i++){ |
| 132 | + dxl.torqueOff(DXL_ID_LIST[i]); |
| 133 | + dxl.setOperatingMode(DXL_ID_LIST[i], OP_POSITION); |
| 134 | + } |
| 135 | + dxl.torqueOn(BROADCAST_ID); |
| 136 | + |
| 137 | + // Fill the members of structure to syncRead using external user packet buffer |
| 138 | + sr_infos.packet.p_buf = user_pkt_buf; |
| 139 | + sr_infos.packet.buf_capacity = user_pkt_buf_cap; |
| 140 | + sr_infos.packet.is_completed = false; |
| 141 | + sr_infos.addr = SR_START_ADDR; |
| 142 | + sr_infos.addr_length = SR_ADDR_LEN; |
| 143 | + sr_infos.p_xels = info_xels_sr; |
| 144 | + sr_infos.xel_count = 0; |
| 145 | + |
| 146 | + for(i=0; i<DXL_ID_CNT; i++){ |
| 147 | + info_xels_sr[i].id = DXL_ID_LIST[i]; |
| 148 | + info_xels_sr[i].p_recv_buf = (uint8_t*)&sr_data[i]; |
| 149 | + sr_infos.xel_count++; |
| 150 | + } |
| 151 | + sr_infos.is_info_changed = true; |
| 152 | + |
| 153 | + // Fill the members of structure to syncWrite using internal packet buffer |
| 154 | + sw_infos.packet.p_buf = nullptr; |
| 155 | + sw_infos.packet.is_completed = false; |
| 156 | + sw_infos.addr = SW_START_ADDR; |
| 157 | + sw_infos.addr_length = SW_ADDR_LEN; |
| 158 | + sw_infos.p_xels = info_xels_sw; |
| 159 | + sw_infos.xel_count = 0; |
| 160 | + |
| 161 | + for(i=0; i<DXL_ID_CNT; i++){ |
| 162 | + info_xels_sw[i].id = DXL_ID_LIST[i]; |
| 163 | + info_xels_sw[i].p_data = (uint8_t*)&sw_data[i].goal_position; |
| 164 | + sw_infos.xel_count++; |
| 165 | + } |
| 166 | + sw_infos.is_info_changed = true; |
| 167 | +} |
| 168 | + |
| 169 | +void loop() { |
| 170 | + // put your main code here, to run repeatedly: |
| 171 | + static uint32_t try_count = 0; |
| 172 | + uint8_t i, recv_cnt; |
| 173 | + |
| 174 | + for(i=0; i<DXL_ID_CNT; i++){ |
| 175 | + sw_data[i].goal_position = goal_position[direction]; |
| 176 | + } |
| 177 | + sw_infos.is_info_changed = true; |
| 178 | + |
| 179 | + DEBUG_SERIAL.print("\n>>>>>> Sync Instruction Test : "); |
| 180 | + DEBUG_SERIAL.println(try_count++); |
| 181 | + if(dxl.syncWrite(&sw_infos) == true){ |
| 182 | + DEBUG_SERIAL.println("[SyncWrite] Success"); |
| 183 | + for(i=0; i<sw_infos.xel_count; i++){ |
| 184 | + DEBUG_SERIAL.print(" ID: ");DEBUG_SERIAL.println(sw_infos.p_xels[i].id); |
| 185 | + DEBUG_SERIAL.print("\t Goal Position: ");DEBUG_SERIAL.println(sw_data[i].goal_position); |
| 186 | + } |
| 187 | + if(direction == 0) |
| 188 | + direction = 1; |
| 189 | + else |
| 190 | + direction = 0; |
| 191 | + }else{ |
| 192 | + DEBUG_SERIAL.print("[SyncWrite] Fail, Lib error code: "); |
| 193 | + DEBUG_SERIAL.print(dxl.getLastLibErrCode()); |
| 194 | + } |
| 195 | + DEBUG_SERIAL.println(); |
| 196 | + |
| 197 | + delay(250); |
| 198 | + |
| 199 | + recv_cnt = dxl.syncRead(&sr_infos); |
| 200 | + if(recv_cnt > 0){ |
| 201 | + DEBUG_SERIAL.print("[SyncRead] Success, Received ID Count: "); |
| 202 | + DEBUG_SERIAL.println(recv_cnt); |
| 203 | + for(i=0; i<recv_cnt; i++){ |
| 204 | + DEBUG_SERIAL.print(" ID: ");DEBUG_SERIAL.print(sr_infos.p_xels[i].id); |
| 205 | + DEBUG_SERIAL.print(", Error: ");DEBUG_SERIAL.println(sr_infos.p_xels[i].error); |
| 206 | + DEBUG_SERIAL.print("\t Present Position: ");DEBUG_SERIAL.println(sr_data[i].present_position); |
| 207 | + } |
| 208 | + }else{ |
| 209 | + DEBUG_SERIAL.print("[SyncRead] Fail, Lib error code: "); |
| 210 | + DEBUG_SERIAL.println(dxl.getLastLibErrCode()); |
| 211 | + } |
| 212 | + DEBUG_SERIAL.println("======================================================="); |
| 213 | + |
| 214 | + digitalWrite(LED_BUILTIN, !digitalRead(LED_BUILTIN)); |
| 215 | + delay(750); |
| 216 | +} |
0 commit comments