AX-11A connects to PC and can be controlle through DYNAMIXEL wizard. But I cant control it through OPECM board and Openm exp board downloading the program through ARDUINO IDE i have the board configured and the port chosen but it doesnt work and when i ping it it gives error code 3 TIMEOUT. How can i fix it
PING has not been working properly for me since 2022, so I do not rely on that Function anymore. Just use the needed Functions such as dxl.setGoalPosition() or dxl.getPresentPosition() directly.
Are you using Arduino IDE 2.3.6? For some reasons, the Arduino backend does not recognize the OpenCM904 properly anymore. See picture below:
Thus when you use the OpenCM-904 and 485-EXP boards, you have to explicitly define the DXL PORT and DIRECTIONAL PIN inside your code. See Lines 19 and 21 in the previous picture. HOWEVER for your case, using AX-12A connected to the 485-EXP board, you will need to use Serial3 and 22, i.e.:
#define DXL_SERIAL Serial3 const int DXL_DIR_PIN = 22;
In short, you cannot rely on the big chunk of if defined() etc… inside the ROBOTIS sample sketches to set the DXL_SERIAL and DXL_DIR_PIN properly for the user anymore (see picture below).
And here is the complete code, it is derived from ROBOTIS example “position_mode.ino”
#include <Dynamixel2Arduino.h>
#define DXL_SERIAL Serial3 //OpenCM9.04 DXL Serial Port (Serial1 for DXL port on OpenCM 9.04 board, Serial3 on 485-EXP)
#define DEBUG_SERIAL Serial
const int DXL_DIR_PIN = 22; //OpenCM9.04 DIR PIN. (28 for DXL port on the OpenCM 9.04 board, 22 for 485-EXP)
const uint8_t DXL_ID = 1;
const float DXL_PROTOCOL_VERSION = 1.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 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_POSITION);
dxl.torqueOn(DXL_ID);
// Limit the maximum velocity in Position Control Mode. Use 0 for Max speed
dxl.writeControlTableItem(PROFILE_VELOCITY, DXL_ID, 70);
}
void loop() {
// put your main code here, to run repeatedly:
// Please refer to e-Manual(http://emanual.robotis.com/docs/en/parts/interface/dynamixel_shield/) for available range of value.
// Set Goal Position in RAW value
dxl.setGoalPosition(DXL_ID, 1000);
int i_present_position = 0;
float f_present_position = 0.0;
while (abs(1000 - i_present_position) > 10)
{
i_present_position = dxl.getPresentPosition(DXL_ID);
DEBUG_SERIAL.print("Present_Position(raw) : ");
DEBUG_SERIAL.println(i_present_position);
}
delay(1000);
// Set Goal Position in DEGREE value
dxl.setGoalPosition(DXL_ID, 5.7, UNIT_DEGREE);
while (abs(5.7 - f_present_position) > 2.0)
{
f_present_position = dxl.getPresentPosition(DXL_ID, UNIT_DEGREE);
DEBUG_SERIAL.print("Present_Position(degree) : ");
DEBUG_SERIAL.println(f_present_position);
}
delay(1000);
}
And here is a little video clip for the run-time performance
This still doesnt work. I have the right baudrate and protocol, id. But it turns out out that we have different exp.boards. I have some rare board, little info about it online. I have the applied robotics STEM board. It came with a manual but it didnt work. Cant upload photos yet.
There is only ONE version of the 485-EXP that I know of. If you use another type of board then you should go to that company that you bought it from to ask questions.