|
| 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 | +/* |
| 18 | + This is an example deprecated. (Not recommended, just an example for legacy) |
| 19 | +*/ |
| 20 | + |
| 21 | +#include <Dynamixel2Arduino.h> |
| 22 | + |
| 23 | +// Please modify it to suit your hardware. |
| 24 | +#if defined(ARDUINO_AVR_UNO) || defined(ARDUINO_AVR_MEGA2560) // When using DynamixelShield |
| 25 | + #include <SoftwareSerial.h> |
| 26 | + SoftwareSerial soft_serial(7, 8); // DYNAMIXELShield UART RX/TX |
| 27 | + #define DXL_SERIAL Serial |
| 28 | + #define DEBUG_SERIAL soft_serial |
| 29 | + const uint8_t DXL_DIR_PIN = 2; // DYNAMIXEL Shield DIR PIN |
| 30 | +#elif defined(ARDUINO_SAM_DUE) // When using DynamixelShield |
| 31 | + #define DXL_SERIAL Serial |
| 32 | + #define DEBUG_SERIAL SerialUSB |
| 33 | + const uint8_t DXL_DIR_PIN = 2; // DYNAMIXEL Shield DIR PIN |
| 34 | +#elif defined(ARDUINO_SAM_ZERO) // When using DynamixelShield |
| 35 | + #define DXL_SERIAL Serial1 |
| 36 | + #define DEBUG_SERIAL SerialUSB |
| 37 | + const uint8_t DXL_DIR_PIN = 2; // DYNAMIXEL Shield DIR PIN |
| 38 | +#elif defined(ARDUINO_OpenCM904) // When using official ROBOTIS board with DXL circuit. |
| 39 | + #define DXL_SERIAL Serial3 //OpenCM9.04 EXP Board's DXL port Serial. (Serial1 for the DXL port on the OpenCM 9.04 board) |
| 40 | + #define DEBUG_SERIAL Serial |
| 41 | + 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) |
| 42 | +#elif defined(ARDUINO_OpenCR) // When using official ROBOTIS board with DXL circuit. |
| 43 | + // For OpenCR, there is a DXL Power Enable pin, so you must initialize and control it. |
| 44 | + // Reference link : https://github.com/ROBOTIS-GIT/OpenCR/blob/master/arduino/opencr_arduino/opencr/libraries/DynamixelSDK/src/dynamixel_sdk/port_handler_arduino.cpp#L78 |
| 45 | + #define DXL_SERIAL Serial3 |
| 46 | + #define DEBUG_SERIAL Serial |
| 47 | + const uint8_t DXL_DIR_PIN = 84; // OpenCR Board's DIR PIN. |
| 48 | +#else // Other boards when using DynamixelShield |
| 49 | + #define DXL_SERIAL Serial1 |
| 50 | + #define DEBUG_SERIAL Serial |
| 51 | + const uint8_t DXL_DIR_PIN = 2; // DYNAMIXEL Shield DIR PIN |
| 52 | +#endif |
| 53 | + |
| 54 | +/* XelInfoForBulkReadParam_t |
| 55 | + A structure that contains the information needed for the parameters of the 'bulkRead packet'. |
| 56 | +
|
| 57 | + typedef struct ParamForBulkReadInst{ |
| 58 | + uint8_t id_count; |
| 59 | + XelInfoForBulkReadParam_t xel[DXL_MAX_NODE]; //refer to below. |
| 60 | + } ParamForBulkReadInst_t; |
| 61 | +
|
| 62 | + typedef struct XelInfoForBulkReadParam{ |
| 63 | + uint8_t id; |
| 64 | + uint16_t addr; |
| 65 | + uint16_t length; |
| 66 | + } XelInfoForBulkReadParam_t; |
| 67 | +*/ |
| 68 | + |
| 69 | +/* XelInfoForBulkWriteParam_t |
| 70 | + A structure that contains the information needed for the parameters of the 'bulkWrite packet'. |
| 71 | +
|
| 72 | + typedef struct ParamForBulkWriteInst{ |
| 73 | + uint8_t id_count; |
| 74 | + XelInfoForBulkWriteParam_t xel[DXL_MAX_NODE]; //refer to below. |
| 75 | + } ParamForBulkWriteInst_t; |
| 76 | +
|
| 77 | + typedef struct XelInfoForBulkWriteParam{ |
| 78 | + uint8_t id; |
| 79 | + uint16_t addr; |
| 80 | + uint16_t length; |
| 81 | + uint8_t data[DXL_MAX_NODE_BUFFER_SIZE]; |
| 82 | + } XelInfoForBulkWriteParam_t; |
| 83 | +*/ |
| 84 | + |
| 85 | +/* RecvInfoFromStatusInst_t |
| 86 | + A structure used to receive data from multiple XELs. |
| 87 | +
|
| 88 | + typedef struct RecvInfoFromStatusInst{ |
| 89 | + uint8_t id_count; |
| 90 | + XelInfoForStatusInst_t xel[DXL_MAX_NODE]; //refer to below. |
| 91 | + } RecvInfoFromStatusInst_t; |
| 92 | +
|
| 93 | + typedef struct XelInfoForStatusInst{ |
| 94 | + uint8_t id; |
| 95 | + uint16_t length; |
| 96 | + uint8_t error; |
| 97 | + uint8_t data[DXL_MAX_NODE_BUFFER_SIZE]; |
| 98 | + } XelInfoForStatusInst_t; |
| 99 | +*/ |
| 100 | + |
| 101 | +ParamForBulkReadInst_t bulk_read_param; |
| 102 | +ParamForBulkWriteInst_t bulk_write_param; |
| 103 | +RecvInfoFromStatusInst_t read_result; |
| 104 | + |
| 105 | +Dynamixel2Arduino dxl(DXL_SERIAL, DXL_DIR_PIN); |
| 106 | + |
| 107 | +void setup() { |
| 108 | + // put your setup code here, to run once: |
| 109 | + DEBUG_SERIAL.begin(115200); |
| 110 | + dxl.begin(57600); |
| 111 | + dxl.scan(); |
| 112 | + |
| 113 | + // fill the members of structure for bulkWrite |
| 114 | + bulk_write_param.xel[0].id = 1; |
| 115 | + bulk_write_param.xel[1].id = 2; |
| 116 | + bulk_write_param.xel[0].addr = 116; //Goal Position on X serise |
| 117 | + bulk_write_param.xel[1].addr = 104; //Goal Velocity on X serise |
| 118 | + bulk_write_param.xel[0].length = 4; |
| 119 | + bulk_write_param.xel[1].length = 4; |
| 120 | + bulk_write_param.id_count = 2; |
| 121 | + |
| 122 | + // fill the members of structure for bulkRead |
| 123 | + bulk_read_param.xel[0].id = 1; |
| 124 | + bulk_read_param.xel[1].id = 2; |
| 125 | + bulk_read_param.xel[0].addr = 132; //Present Position on X serise |
| 126 | + bulk_read_param.xel[1].addr = 128; //Present Velocity on X serise |
| 127 | + bulk_read_param.xel[0].length = 4; |
| 128 | + bulk_read_param.xel[1].length = 4; |
| 129 | + bulk_read_param.id_count = 2; |
| 130 | + |
| 131 | + dxl.torqueOff(1); |
| 132 | + dxl.setOperatingMode(1, OP_POSITION); |
| 133 | + dxl.torqueOn(1); |
| 134 | + |
| 135 | + dxl.torqueOff(3); |
| 136 | + dxl.setOperatingMode(3, OP_VELOCITY); |
| 137 | + dxl.torqueOn(3); |
| 138 | +} |
| 139 | + |
| 140 | +void loop() { |
| 141 | + // put your main code here, to run repeatedly: |
| 142 | + static int32_t position = 0, velocity = 0; |
| 143 | + int32_t recv_position = 0, recv_velocity = 0; |
| 144 | + |
| 145 | + // set value to data buffer for bulkWrite |
| 146 | + position = position >= 4095 ? 0 : position+409; |
| 147 | + memcpy(bulk_write_param.xel[0].data, &position, sizeof(position)); |
| 148 | + velocity = velocity >= 200 ? -200 : velocity+10; |
| 149 | + memcpy(bulk_write_param.xel[1].data, &velocity, sizeof(velocity)); |
| 150 | + |
| 151 | + // send command using bulkWrite |
| 152 | + dxl.bulkWrite(bulk_write_param); |
| 153 | + delay(100); |
| 154 | + |
| 155 | + // Print the read data using bulkRead |
| 156 | + dxl.bulkRead(bulk_read_param, read_result); |
| 157 | + DEBUG_SERIAL.println(F("======= Bulk Read ========")); |
| 158 | + memcpy(&recv_position, read_result.xel[0].data, read_result.xel[0].length); |
| 159 | + memcpy(&recv_velocity, read_result.xel[1].data, read_result.xel[1].length); |
| 160 | + DEBUG_SERIAL.print(F("ID: "));DEBUG_SERIAL.print(read_result.xel[0].id);DEBUG_SERIAL.print(" "); |
| 161 | + DEBUG_SERIAL.print(F(", Present Position: "));DEBUG_SERIAL.print(recv_position);DEBUG_SERIAL.print(" "); |
| 162 | + DEBUG_SERIAL.print(F(", Packet Error: "));DEBUG_SERIAL.print(read_result.xel[0].error);DEBUG_SERIAL.print(" "); |
| 163 | + DEBUG_SERIAL.print(F(", Param Length: "));DEBUG_SERIAL.print(read_result.xel[0].length);DEBUG_SERIAL.print(" "); |
| 164 | + DEBUG_SERIAL.println(); |
| 165 | + DEBUG_SERIAL.print(F("ID: "));DEBUG_SERIAL.print(read_result.xel[1].id);DEBUG_SERIAL.print(" "); |
| 166 | + DEBUG_SERIAL.print(F(", Present Velocity: "));DEBUG_SERIAL.print(recv_velocity);DEBUG_SERIAL.print(" "); |
| 167 | + DEBUG_SERIAL.print(F(", Packet Error: "));DEBUG_SERIAL.print(read_result.xel[1].error);DEBUG_SERIAL.print(" "); |
| 168 | + DEBUG_SERIAL.print(F(", Param Length: "));DEBUG_SERIAL.print(read_result.xel[1].length);DEBUG_SERIAL.print(" "); |
| 169 | + DEBUG_SERIAL.println(); |
| 170 | + DEBUG_SERIAL.println(); |
| 171 | + delay(100); |
| 172 | +} |
| 173 | + |
| 174 | + |
0 commit comments