Quick update: I thought I would try some of it out with the recent T4 board I assembled...
Found out I screwed up on the board and when I did a copy and paste of a couple of resistors, I forget to edit the values so I built the board with 2 wrong resistors, instead of begin something like 4.7KOhm, they were supposed to be 47 and 333 ohm...
Luckily I was able to remove the resistors and use some that were reasonably close to these values and now a servo respond...
I tried plugging in one AX-12 and did a quick set of pings to see if it would find it.
I then did a quick move the servos a little, which appears to move. Although not as smooth as I would expect... But may be simple issue with Quick and dirty test...
Code:
#include <Dynamixel2Arduino.h>
// Kurt's T4-T36 board
#define DXL_SERIAL Serial2
const uint8_t DXL_DIR_PIN = 6; // OpenCR Board's DIR PIN.
class NewSerialPortHandler : public DYNAMIXEL::SerialPortHandler
{
public:
NewSerialPortHandler(HardwareSerial& port, const int dir_pin = -1)
: SerialPortHandler(port, dir_pin), port_(port), dir_pin_(dir_pin)
{}
virtual size_t write(uint8_t c) override
{
size_t ret = 0;
digitalWrite(dir_pin_, HIGH);
ret = port_.write(c);
port_.flush();
digitalWrite(dir_pin_, LOW);
return ret;
}
virtual size_t write(uint8_t *buf, size_t len) override
{
size_t ret;
digitalWrite(dir_pin_, HIGH);
ret = port_.write(buf, len);
port_.flush();
digitalWrite(dir_pin_, LOW);
return ret;
}
private:
HardwareSerial& port_;
const int dir_pin_;
};
Dynamixel2Arduino dxl;
NewSerialPortHandler dxl_port(DXL_SERIAL, DXL_DIR_PIN);
uint8_t id = 0xff;
float goal_pos = 512.0;
float max_delta = 128.0;
float incr = 1.0;
float center_pos;
void setup() {
// put your setup code here, to run once:
// Use Serial to debug.
while (!Serial && millis() < 5000) ;
Serial.begin(115200);
// Set Port instance
dxl.setPort(dxl_port);
// Set Port baudrate to 1000000. This has to match with DYNAMIXEL baudrate.
dxl.begin(1000000);
// Set Port Protocol Version. This has to match with DYNAMIXEL protocol version.
Serial.println("Setup completed");
Serial.flush();
}
uint8_t findServo() {
Serial.println("Search for a Servo");
Serial.println("First try Protocol 1");
dxl.setPortProtocolVersion(1.0);
for (uint8_t servo_id = 0; servo_id < 253; servo_id++) {
if (dxl.ping(servo_id) == true) {
Serial.printf("Found ID:%u Model Number:%u\n", servo_id, dxl.getModelNumber(servo_id));
center_pos = goal_pos = 512.0;
max_delta = 128.0;
incr = 1.0;
return servo_id;
}
}
Serial.println("Now try Protocol 2");
dxl.setPortProtocolVersion(2.0);
for (uint8_t servo_id = 0; servo_id < 253; servo_id++) {
if (dxl.ping(servo_id) == true) {
Serial.printf("Found ID:%u Model Number:%u\n", servo_id, dxl.getModelNumber(servo_id));
center_pos = goal_pos = 2048.0;
max_delta = 256.0;
incr = 2.0;
return servo_id;
}
}
Serial.println("No Servos found");
return 0xff;
}
void loop() {
if (id == 0xff) {
id = findServo();
if (id == 0xff) {
delay(1000);
return;
}
dxl.torqueOn(id);
}
goal_pos += incr;
if (goal_pos >= (center_pos + max_delta)) incr = -incr;
if (goal_pos <= (center_pos - max_delta)) incr = -incr;
dxl.setGoalPosition(id, goal_pos);
if (Serial.available()) {
Serial.println("Paused");
while (Serial.read() != -1);
while (Serial.read() == -1);
while (Serial.read() != -1);
}
}