How to control 2 AX12W independently with OpenCR 1.0

Hi everyone, I’m currently using OpenCR 1.0 and 2 AX-12W for my project but I got some problems below:

  1. I couldn’t scan those 2 AX-12W in Dynamixel Wizard 2.0, I don’t know if I need any equipment else beside OpenCR 1.0 (I connected 2 servos into OpenCR and OpenCR directly into my PC)
  2. I used the sync_write in Arduino IDE and compiled into my OpenCR but those 2 servos didn’t work
  3. How could I use the gyro that existing on OpenCR

Thank you all for your helps!! ^^

  1. In order to connect your AX-12W servos to your PC using the OpenCR, you’ll need to upload the USB2DXL example sketch to your OpenCR board.
  2. Before connecting multiple servos to the same network, you need to assign them different ID numbers, otherwise, they will both fail to be detected.
  3. The OpenCR Git repository has some premade example sketches that can help show you how to program the IMU
1 Like
  1. So there is no way else to connect and control AX-12W directly from OpenCR ?
  2. I changed the ID successfully and available to contronl 2 AX-12Ws independently by Arduini Uno+Dynamixel Shield, thanks.
  3. As I read on that link, the program is used for MPU9250. However, I now utilize the new OpenCR with ICM-20648, I don’t know whether it compatible or not.

Thanks for your reply

for the 3. I found out the library helping me to program the IMU.

Thank you

You are confusing me now. You are using Arduino IDE with OpenCR and I am assuming that you have installed the OpenCR board via the Board Manager - so why would you need to use the Arduino UNO + Shield? Also have you installed the Dynamixel2Arduino library? If you have done these 2 tasks, there should be a bunch of example sketches showing how to control the DXLs from OpenCR directly.

image

Below is a complete Arduino sketch testing some XL-430 with OpenCR-1 and the Dynamixel2Arduino library:

#include <Dynamixel2Arduino.h>

#define DXL_SERIAL   Serial3  // for OpenCR
#define DEBUG_SERIAL Serial
const int DXL_DIR_PIN = 84; // OpenCR Board's DIR PIN.
const uint8_t DXL_ID = 1;
const float DXL_PROTOCOL_VERSION = 2.0;  // 1.0 for AX-12

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 UART port of DYNAMIXEL Shield to debug.
  DEBUG_SERIAL.begin(115200);
  while(!DEBUG_SERIAL);
  
  // Set Port baudrate to 1000000 bps. This has to match with DYNAMIXEL baudrate.
  dxl.begin(1000000);
  // Set Port Protocol Version. This has to match with DYNAMIXEL protocol version.
  dxl.setPortProtocolVersion(DXL_PROTOCOL_VERSION);
  // Get DYNAMIXEL information
  dxl.ping(DXL_ID);

  // Turn off torque when configuring items in EEPROM area
  dxl.torqueOff(DXL_ID);
  dxl.setOperatingMode(DXL_ID, OP_VELOCITY);
  dxl.torqueOn(DXL_ID);
}

void loop() {
  // Set Goal Velocity using RAW unit
  dxl.setGoalVelocity(DXL_ID, 200);
  delay(1000);
  // Print present velocity
  DEBUG_SERIAL.print("Present Velocity(raw) : ");
  DEBUG_SERIAL.println(dxl.getPresentVelocity(DXL_ID));
  delay(1000);

  // Set Goal Velocity using RPM
  dxl.setGoalVelocity(DXL_ID, 25.8, UNIT_RPM);
  delay(1000);
  DEBUG_SERIAL.print("Present Velocity(rpm) : ");
  DEBUG_SERIAL.println(dxl.getPresentVelocity(DXL_ID, UNIT_RPM));
  delay(1000);

  // Set Goal Velocity using percentage (-100.0 [%] ~ 100.0 [%])
  dxl.setGoalVelocity(DXL_ID, -10.2, UNIT_PERCENT);
  delay(1000);
  DEBUG_SERIAL.print("Present Velocity(ratio) : ");
  DEBUG_SERIAL.println(dxl.getPresentVelocity(DXL_ID, UNIT_PERCENT));
  delay(1000);
}

To make it work with AX-12s, all you have to do is to change DXL_PROTOCOL_VERSION = 1.0

OpenCR_Velocity_Mode

Below is a picture of my physical setup:

IMG_026488

And a video clip of a SyncWriteRead sketch (using 2XL430):

thank you for your reply, I could solve my problem