ROBOTIS-GIT / Dynamixel2Arduino

DYNAMIXEL protocol library for Arduino
Apache License 2.0
88 stars 55 forks source link

Velocity Mode Reverse #83

Open WilliamH07 opened 3 years ago

WilliamH07 commented 3 years ago

Hello, I recently wanted to use a joystick for my robot arm to control a XL320, it's working perfectly but when I modify the code to make it move in reverse nothing is happening. I really don't understand why in velocity mode with RAW UNIT it's not working but with percent it's working. Since I use a joystick I need to use the RAW unit. I post the code I use below. Btw I use a PS5 controller as the joystick in bluetooth with a shield. Even when I put a negative number instead of the input of the ps5 controller nothing is happening

#include <PS5BT.h>
#include <usbhub.h>

// Satisfy the IDE, which needs to see the include statment in the ino too.
#ifdef dobogusinclude
#include <spi4teensy3.h>
#endif
#include <SPI.h>

USB Usb;
//USBHub Hub1(&Usb); // Some dongles have a hub inside
BTD Btd(&Usb); // You have to create the Bluetooth Dongle instance like so

/* You can create the instance of the PS5BT class in two ways */
// This will start an inquiry and then pair with the PS5 controller - you only have to do this once
// You will need to hold down the PS and Share button at the same time, the PS5 controller will then start to blink rapidly indicating that it is in pairing mode
PS5BT PS5(&Btd, PAIR);
bool printAngle = false, printTouch = false;
uint16_t lastMessageCounter = -1;
uint8_t player_led_mask = 0;
bool microphone_led = false;
uint32_t ps_timer;

#include <Dynamixel2Arduino.h>
#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

const uint8_t DXL_ID = 1;
const float DXL_PROTOCOL_VERSION = 2.0;
int val = 0;
int sensVal = 0;
int sensValR3 = 0;
DynamixelShield dxl;

//This namespace is required to use Control table item names
using namespace ControlTableItem;

void setup() {
  // put your setup code here, to run once:

  // For Uno, Nano, Mini, and Mega, use UART port of DYNAMIXEL Shield to debug.
  DEBUG_SERIAL.begin(115200);

  // 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(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);

   #if !defined(__MIPSEL__)
  while (!Serial); // Wait for serial port to connect - used on Leonardo, Teensy and other boards with built-in USB CDC serial connection
#endif
  if (Usb.Init() == -1) {
    Serial.print(F("\r\nOSC did not start"));
    while (1); // Halt
  }
  Serial.print(F("\r\nPS5 Bluetooth Library Started"));
}

void loop() {
       Usb.Task();
   if (PS5.connected() && lastMessageCounter != PS5.getMessageCounter()) {
    lastMessageCounter = PS5.getMessageCounter();  
    if (PS5.getButtonPress(PS)) {
      if (millis() - ps_timer > 1000)
        PS5.disconnect();
    } else
      ps_timer = millis();

  sensVal = (PS5.getAnalogButton(L2));
  val = constrain(sensVal, 0, 180);
  sensValR3 = (val) - (2*(val));
  // Please refer to e-Manual(http://emanual.robotis.com) for available range of value. 
  // Set Goal Velocity using RA unit
 dxl.setGoalVelocity(DXL_ID, sensValR3);

}
}

Thanks, WilliamH07

ROBOTIS-Will commented 3 years ago

Hi @WilliamH07

I'm sorry about the delayed response.

Unlike other X series, the range of velocity of XL-320 is 0 ~ 2047, and as described in the Moving Speed(32) section of the XL-320 eManual, the CW rotation is achieved by sending a value between 1024 and 2047. Please note that the bit 10 in the data represents the direction of the rotation.

For example, 1024 (0x400) is 0 in the CW direction, and 2047 (0x7FF) is the maximum speed in the CW direction. (max CCW) 1023 <-- 0 (stop) 1024 --> 2047 (max CW)

Thanks you.

ROBOTIS-David commented 3 years ago

Hello @WilliamH07

The following loop() code allow me to control the direction of the DYNAMIXEL with raw values (*Make a simple code change from Dynamixel Shield Example: _velocitymode ) Please feel free to test it.

void loop() {
  // put your main code here, to run repeatedly:

  // Please refer to e-Manual(http://emanual.robotis.com) for available range of value. 
  // Set Goal Velocity using RAW unit
  dxl.setGoalVelocity(DXL_ID, 1523); // CCW 
  delay(1000);
  // Print present velocity
  DEBUG_SERIAL.print("Present Velocity(raw) : ");
  DEBUG_SERIAL.println(dxl.getPresentVelocity(DXL_ID));
  delay(1000);

  dxl.setGoalVelocity(DXL_ID, 500); // CW
  delay(1000);
  // Print present velocity
  DEBUG_SERIAL.print("Present Velocity(raw) : ");
  DEBUG_SERIAL.println(dxl.getPresentVelocity(DXL_ID));
  delay(1000);
}
WilliamH07 commented 3 years ago

Hello, Thanks for your reply, and sorry for the late respond I try something different using percent, and it works pretty well, it need adjustment but it works ! Thanks WilliamH07