OpenCM 9.04

From Lofaro Lab Wiki
Revision as of 17:15, 27 January 2015 by Dlofaro (Talk | contribs)

Jump to: navigation, search

Overview

ROBOTIS OpenCM

The ROBOTIS OpenCM is a development Software and download tool for the OpenCM9.04 embedded board. Sources of the ROBOTIS OpenCM are released under licenses of their respective authors Copyright (c) ROBOTIS Co., Ltd. Modified or newly-created codes are released under the GNUGPL or LGPL licenses. For more information on the OpenCM9.04 refer to the Appendix section of the e-manuals

This tutorial is made to supplement that given by ROBOTIS.

OpenCM9.04 Software and Installation

OpenCM9.04 uses the ROBOTIS OpenCM Integrated Developmental Environment (IDE) to allow users to program with ease. The download link for the ROBOTIS OpenCM IDE can be found below:

Downloads

Installation

Dependencies

Linux (Ubuntu)

Java:

sudo apt-get install openjdk-7-jdk

ARM Toolchain:

sudo apt-get install ia32-libs

Permissions for serial port (ttyACM0 is the name of the OpencM 9.04 serial port):

sudo chmod 777 /dev/ttyACM0

Trouble Shooting

Board is not responding

If you get the message "Board is not responding" when trying to "download" do the following:

  • Remove all power from the device
  • Hold down the "user" button
  • Turn power back on while the "user" button is pressed
  • Release the "user" button and "download" again. (note: you might have to "download" multiple times before it works)

Examples

This section shows examples of using the OpemCM 9.04 with Dynamixel actuators. Most code comes from the examples built into the ROBOTIS OpenCM software.

Set Position Example

This example shows how set the position of a Dynamixel (XL-320) with ID 1. The position is set to 0 encoder ticks, sleeps for one second, then is set to 300 encoder ticks, then sleeps for one second, the repeats.

/* Dynamixel ID Change Example
 
Turns the dynamixel left , then turn right for one 
 second, repeatedly.
 
               Compatibility
 CM900                  O
 OpenCM9.04             O
 
                   Dynamixel Compatibility
               AX    MX      RX    XL-320    Pro
 CM900          O      O      O        O      X
 OpenCM9.04     O      O      O        O      X
 **** OpenCM 485 EXP board is needed to use 4 pin Dynamixel and Pro Series ****
 
 
 created 22 May 2014
 by ROBOTIS CO,.LTD.
 */
 /* Serial device defines for dxl bus */
#define DXL_BUS_SERIAL1 1  //Dynamixel on Serial1(USART1)  <-OpenCM9.04
#define DXL_BUS_SERIAL2 2  //Dynamixel on Serial2(USART2)  <-LN101,BT210
#define DXL_BUS_SERIAL3 3  //Dynamixel on Serial3(USART3)  <-OpenCM 485EXP
/* Dynamixel ID defines */
#define J_ID 1
 
Dynamixel Dxl(DXL_BUS_SERIAL1); 
 
void setup() {
  // Initialize the dynamixel bus:
  // Dynamixel 2.0 Baudrate -> 0: 9600, 1: 57600, 2: 115200, 3: 1Mbps  
  Dxl.begin(3);  
  Dxl.jointMode(J_ID); //jointMode() is to use position mode  
}
 
void loop() {
  /*Turn dynamixel ID 1 to position 0*/
  Dxl.goalPosition(J_ID, 0); 
  // Wait for 1 second (1000 milliseconds)
  delay(1000);              
  /*Turn dynamixel ID 1 to position 300*/
  Dxl.goalPosition(J_ID, 300);
  // Wait for 1 second (1000 milliseconds)
  delay(1000);              
}

Change Motor ID Example

This example shows how to change the motor ID of a Dynamixel (XL-320) with any motor ID to ID 2. It will set all actuators on the bus to ID 2 thus ONLY HAVE ONE DYNAMIXEL PLUGGED IN WHILE SETTING THE ID.

/* Dynamixel ID Change Example
 
 Dynamixel ID Change 
 
               Compatibility
 CM900                  O
 OpenCM9.04             O
 
                   Dynamixel Compatibility
               AX    MX      RX    XL-320    Pro
 CM900          O      O      O        O      X
 OpenCM9.04     O      O      O        O      X
 **** OpenCM 485 EXP board is needed to use 4 pin Dynamixel and Pro Series ****
 
 
 created 22 May 2014
 by ROBOTIS CO,.LTD.
 */
 /* Serial device defines for dxl bus */
#define DXL_BUS_SERIAL1 1  //Dynamixel on Serial1(USART1)  <-OpenCM9.04
#define DXL_BUS_SERIAL2 2  //Dynamixel on Serial2(USART2)  <-LN101,BT210
#define DXL_BUS_SERIAL3 3  //Dynamixel on Serial3(USART3)  <-OpenCM 485EXP
/* Dynamixel ID defines */
#define NEW_ID 2
 
Dynamixel Dxl(DXL_BUS_SERIAL1); 
 
void setup() {
  // Initialize the dynamixel bus:
  // Dynamixel 2.0 Baudrate -> 0: 9600, 1: 57600, 2: 115200, 3: 1Mbps  
  Dxl.begin(3);  
/*************** CAUTION ***********************
 * All dynamixels in bus will be changed to ID 2 by using broadcast ID(0xFE)
 * Please check if there is only one dynamixel that you want to change ID
 ************************************************/
  Dxl.setID(BROADCAST_ID, NEW_ID);  //Dynamixel_Id_Change 1 to 2
  Dxl.jointMode(NEW_ID); //jointMode() is to use position mode  
}
 
void loop() {
  // Wait for 1 second (1000 milliseconds)
  delay(1000);              
}

Wheel Spin Example

This example shows how to spin a Dynamixel (XL-320) with motor ID 1 in continuous spin mode CW and CC for a period of 5 seconds each then stop for 2 seconds. This will repeat indefinitely.

/* Dynamixel Wheel Mode Example
 
 This example shows how to use dynamixel as wheel mode
 All dynamixels are set as joint mode in factory,
 but if you want to make a wheel using dynamixel, 
 you have to change it to wheel mode by change controlmode to 1
 
                 Compatibility
 CM900                  O
 OpenCM9.04             O
 
                 Dynamixel Compatibility
               AX    MX      RX    XL-320    Pro
 CM900          O      O      O        O      X
 OpenCM9.04     O      O      O        O      X
 **** OpenCM 485 EXP board is needed to use 4 pin Dynamixel and Pro Series ****
 
 created 22 May 2014
 by ROBOTIS CO,.LTD.
 */
#define DXL_BUS_SERIAL1 1  //Dynamixel on Serial1(USART1)  <-OpenCM9.04
#define DXL_BUS_SERIAL2 2  //Dynamixel on Serial2(USART2)  <-LN101,BT210
#define DXL_BUS_SERIAL3 3  //Dynamixel on Serial3(USART3)  <-OpenCM 485EXP
 
#define ID_NUM 1
 
Dynamixel Dxl(DXL_BUS_SERIAL1);
 
void setup() {
  // Initialize the dynamixel bus:
 
  // Dynamixel 2.0 Baudrate -> 0: 9600, 1: 57600, 2: 115200, 3: 1Mbps 
  Dxl.begin(3);
  Dxl.wheelMode(ID_NUM); //wheelMode() is to use wheel mode
}
 
void loop() {
  Dxl.goalSpeed(ID_NUM, 400); //forward
  delay(5000);
  Dxl.goalSpeed(ID_NUM, 400 | 0x400); //reverse
  delay(5000); 
  Dxl.goalSpeed(ID_NUM, 0); //stop
  delay(2000);
}