You are probably right that it was not tested (That is the Hardware UART
code base on the UNO R4 boards)
Sorry I have not done anything with this in awhile now.
Note: you probably don't need to change this switch on these boards. That is The USB is not using the same UART as shield pins 0 and 1. So you you should be able to keep it in Dynmixel setting.
At one point I had it working. Example sketch, to scan dynamixels:
/*******************************************************************************
* Copyright 2016 ROBOTIS CO., LTD.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*******************************************************************************/
#include <DynamixelShield.h>
#if defined(ARDUINO_AVR_UNO) || defined(ARDUINO_AVR_MEGA2560)
#include <SoftwareSerial.h>
SoftwareSerial soft_serial(7, 8); // DYNAMIXELShield UART RX/TX
#define DEBUG_SERIAL soft_serial
#elif defined(ARDUINO_SAM_DUE) || defined(ARDUINO_SAM_ZERO)
#define DEBUG_SERIAL SerialUSB
#else
#define DEBUG_SERIAL Serial
#endif
//#define MAX_BAUD 5
//const int32_t buad[MAX_BAUD] = {57600, 115200, 1000000, 2000000, 3000000};
#define MAX_BAUD 1
const int32_t buad[MAX_BAUD] = {1000000};
Dynamixel2Arduino dxl(DXL_SERIAL, DXL_DIR_PIN);
//This namespace is required to use Control table item names
using namespace ControlTableItem;
void setup() {
// For Uno, Nano, Mini, and Mega, use UART port of DYNAMIXEL Shield to debug.
DEBUG_SERIAL.begin(115200); //set debugging port baudrate to 115200bps
while(!DEBUG_SERIAL); //Wait until the serial port is opened
#if 1
pinMode(3, OUTPUT);
pinMode(4, OUTPUT);
pinMode(5, OUTPUT);
pinMode(6, OUTPUT);
pinMode(7, OUTPUT);
pinMode(8, OUTPUT);
#endif
}
void loop() {
int8_t index = 0;
int8_t found_dynamixel = 0;
for(int8_t protocol = 1; protocol < 3; protocol++) {
// Set Port Protocol Version. This has to match with DYNAMIXEL protocol version.
dxl.setPortProtocolVersion((float)protocol);
DEBUG_SERIAL.print("SCAN PROTOCOL ");
DEBUG_SERIAL.println(protocol);
delay(10); // give a break between to easier find
for(index = 0; index < MAX_BAUD; index++) {
// Set Port baudrate.
DEBUG_SERIAL.print("SCAN BAUDRATE ");
DEBUG_SERIAL.println(buad[index]);
dxl.begin(buad[index]);
//for(int id = 0; id < DXL_BROADCAST_ID; id++) {
for(int id = 0; id < 25/*DXL_BROADCAST_ID*/; id++) {
//iterate until all ID in each buadrate is scanned.
if(dxl.ping(id)) {
DEBUG_SERIAL.print("ID : ");
DEBUG_SERIAL.print(id);
DEBUG_SERIAL.print(", Model Number: ");
DEBUG_SERIAL.println(dxl.getModelNumber(id));
found_dynamixel++;
}
}
}
}
DEBUG_SERIAL.print("Total ");
DEBUG_SERIAL.print(found_dynamixel);
DEBUG_SERIAL.println(" DYNAMIXEL(s) found!");
DEBUG_SERIAL.println("\n\n*** Press any key to run again ***");
while (DEBUG_SERIAL.read() == -1) ;
while (DEBUG_SERIAL.read() != -1) ;
}
But I don't remember if it was with my SerialX code changes or if I had it working with the released stuff.
There are several issues with the UART code including not buffering, at times bytes lost...
But the main problem is that the Seriax.flush() code was never implemented. The flush call should not return until all of the output bytes have been fully serialized out. It does check to make sure that the unused hardware FIFO queue is empty.
The Dynamixel protocol is half duplex, This shield uses pin 2, to switch the DXL buss from using the RX or TX pin of the UART on pins 0 and 1 by default.
When the code logically sends a command or request out to the servos,
it will set Pin 2 into the TX state, and then it will do Serial1.print()/Serial1.write() calls to generate the command, it then calls Serial1.flush() to make sure all of the data has been sent and then switches IO Pin 2 back into RX mode to receive any responses.
The problem is, it cmight still be transmitting, when pin 2 is changed and the cammand is then invalid... So nothing happens.
At one point I put in a delay into the code to make sure the data was sent before it switched back to RX mode.
Hope that makes sense.
More details are probably in my still open issue:
UNO R4 - Library(libraries) - will not build on new Arduino boards... And may not work at all. · Issue #127 · ROBOTIS-GIT/Dynamixel2Arduino (github.com)