Hi, I am using the OpenRB-150 board to control the Dynamxiel actuators. I found one issue when using the Dynamixel2Arduino library and the MPRLS library. The Open-RB 150 works fine with either the Dynamixel2Arduino library or the MPRLS library. However, when I was uploading the code using both libraries, the Arduino IDE always shows COM can’t be found and the Arduino IDE froze.
My code is as following:
The highlighted part is for pressure reading while the non-highlighted part is for Dynamixel, either works fine but fails when integrated.
#include <Dynamixel2Arduino.h>
#include <Wire.h>
#include “Adafruit_MPRLS.h”
// Please modify it to suit your hardware.
#if defined(ARDUINO_AVR_UNO) || defined(ARDUINO_AVR_MEGA2560) // When using DynamixelShield
#include <SoftwareSerial.h>
SoftwareSerial soft_serial(7, 8); // DYNAMIXELShield UART RX/TX
#define DXL_SERIAL Serial
#define DEBUG_SERIAL soft_serial
const int DXL_DIR_PIN = 2; // DYNAMIXEL Shield DIR PIN
#elif defined(ARDUINO_SAM_DUE) // When using DynamixelShield
#define DXL_SERIAL Serial
#define DEBUG_SERIAL SerialUSB
const int DXL_DIR_PIN = 2; // DYNAMIXEL Shield DIR PIN
#elif defined(ARDUINO_SAM_ZERO) // When using DynamixelShield
#define DXL_SERIAL Serial1
#define DEBUG_SERIAL SerialUSB
const int DXL_DIR_PIN = 2; // DYNAMIXEL Shield DIR PIN
#elif defined(ARDUINO_OpenCM904) // When using official ROBOTIS board with DXL circuit.
#define DXL_SERIAL Serial3 //OpenCM9.04 EXP Board’s DXL port Serial. (Serial1 for the DXL port on the OpenCM 9.04 board)
#define DEBUG_SERIAL Serial
const int DXL_DIR_PIN = 22; //OpenCM9.04 EXP Board’s DIR PIN. (28 for the DXL port on the OpenCM 9.04 board)
#elif defined(ARDUINO_OpenCR) // When using official ROBOTIS board with DXL circuit.
// For OpenCR, there is a DXL Power Enable pin, so you must initialize and control it.
// Reference link : OpenCR/arduino/opencr_arduino/opencr/libraries/DynamixelSDK/src/dynamixel_sdk/port_handler_arduino.cpp at master · ROBOTIS-GIT/OpenCR · GitHub
#define DXL_SERIAL Serial3
#define DEBUG_SERIAL Serial
const int DXL_DIR_PIN = 84; // OpenCR Board’s DIR PIN.
#elif defined(ARDUINO_OpenRB) // When using OpenRB-150
//OpenRB does not require the DIR control pin.
#define DXL_SERIAL Serial1
#define DEBUG_SERIAL Serial
const int DXL_DIR_PIN = -1;
#else // Other boards when using DynamixelShield
#define DXL_SERIAL Serial1
#define DEBUG_SERIAL Serial
const int DXL_DIR_PIN = 2; // DYNAMIXEL Shield DIR PIN
#endif
const uint8_t gr_ID = 1;
const uint8_t rt_ID = 2;
const uint8_t df_ID = 3;
const uint8_t fd_ID = 6;
double gr_CP, gr_DP, gr_initial, rt_CP, rt_DP, rt_initial, df_CP, df_DP, df_initial, fd_CP, fd_DP, fd_initial;
unsigned long previousMillis = 0;
const long interval = 4000;
long K8P_level;
long PVQ_level;
Dynamixel2Arduino dxl(DXL_SERIAL, DXL_DIR_PIN);
using namespace ControlTableItem;
const float DXL_PROTOCOL_VERSION = 2.0;
#define RESET_PIN -1 // set to any GPIO pin # to hard-reset on begin()
#define EOC_PIN -1 // set to any GPIO pin to read end-of-conversion by pin
Adafruit_MPRLS mpr = Adafruit_MPRLS(RESET_PIN, EOC_PIN);
void setup(){
pinMode(11,OUTPUT);
pinMode(12,OUTPUT);
DEBUG_SERIAL.begin(57600);
// Set Port baudrate to 57600bps. This has to match with DYNAMIXEL baudrate.
dxl.begin(57600);
// Set Port Protocol Version. This has to match with DYNAMIXEL protocol version.
dxl.setPortProtocolVersion(DXL_PROTOCOL_VERSION);
// Get DYNAMIXEL information
dxl.ping(gr_ID);
dxl.ping(rt_ID);
dxl.ping(df_ID);
// Turn off torque when configuring items in EEPROM area, set PWM mode
dxl.torqueOff(gr_ID);
dxl.setOperatingMode(gr_ID, OP_EXTENDED_POSITION);
dxl.torqueOn(gr_ID);
dxl.writeControlTableItem(PROFILE_VELOCITY, gr_ID, 50);
dxl.torqueOff(rt_ID);
dxl.setOperatingMode(rt_ID, OP_EXTENDED_POSITION);
dxl.torqueOn(rt_ID);
dxl.writeControlTableItem(PROFILE_VELOCITY, rt_ID, 50);
dxl.torqueOff(df_ID);
dxl.setOperatingMode(df_ID, OP_EXTENDED_POSITION);
dxl.torqueOn(df_ID);
dxl.writeControlTableItem(PROFILE_VELOCITY, df_ID, 50);
dxl.torqueOff(fd_ID);
dxl.setOperatingMode(fd_ID, OP_EXTENDED_POSITION);
dxl.torqueOn(fd_ID);
dxl.writeControlTableItem(PROFILE_VELOCITY, fd_ID, 50);
Serial.begin(57600);
}
void loop(){
float pressure_hPa = mpr.readPressure();
** Serial.print("Pressure (KPa): "); Serial.println(pressure_hPa/10);**
** delay(100);**
}