Edit on GitHub

Controller

The open_manipulator_controller package created by ROBOTIS helps to control each joint of OpenMANIPULATOR-X and to check the status of OpenMANIPULATOR-X through ROS messages.
In order to operate the OpenMANIPULATOR-X, the controller package should be running in the first place.

Other experimental controllers are available in the Experimental section.

NOTE:

  • Make sure that dependent packages are installed before performing these instructions - Install ROS Packages

The open_manipulator_controller package created by ROBOTIS helps to control each joint of OpenMANIPULATOR-X and to check the status of OpenMANIPULATOR-X through ROS messages.
In order to operate the OpenMANIPULATOR-X, the controller package should be running in the first place.

Other experimental controllers are available in the Experimental section.

NOTE:

  • Make sure that dependent packages are installed before performing these instructions - Install ROS Packages

OpenMANIPULATOR-X controller provides basic manipulation of OpenMANIPULATOR-X. You can control DYNAMIXEL’s of OpenMANIPULATOR-X and check states of OpenMANIPULATOR-X through messages of the controller.

NOTE:

  • Make sure ROS dependencies are installed before performing these instructions. - Install ROS Packages

OpenMANIPULATOR-X controller provides basic manipulation of OpenMANIPULATOR-X. You can control DYNAMIXEL’s of OpenMANIPULATOR-X and check states of OpenMANIPULATOR-X through messages of the controller.

NOTE:

  • Make sure ROS dependencies are installed before performing these instructions. - Install ROS Packages

Arduino sketch for OpenCR OpenMANIPULATOR-X includes the controller in the code.

Launch Controller

Open a new terminal and launch the open_manipulator_controller package.

  • When operating with U2D2
    $ roslaunch open_manipulator_controller open_manipulator_controller.launch
    
  • When operating with OpenCR
    $ roslaunch open_manipulator_controller open_manipulator_controller.launch usb_port:=/dev/ttyACM0 baud_rate:=1000000
    

The open_manipulator_controller.launch file has several arguments for launching the controller package. Please see below Parameter Descriptions.

WARNING :
Please check each joint position before running OpenMANIPULATOR-X. The manipulator will not operate if any joint is out of operable range.
The following image describes the recommended pose of OpenMANIPULATOR-X at start up. Please adjust the pose before the torque is turned on by the controller.

Follwing message will be shown in the terminal with a successful launch of the controller.

SUMMARY
========

PARAMETERS
 * /open_manipulator/control_period: 0.01
 * /open_manipulator/moveit_sample_duration: 0.05
 * /open_manipulator/planning_group_name: arm
 * /open_manipulator/using_moveit: False
 * /open_manipulator/using_platform: True
 * /rosdistro: kinetic
 * /rosversion: 1.12.14

NODES
  /
    open_manipulator (open_manipulator_controller/open_manipulator_controller)

ROS_MASTER_URI=http://localhost:11311

process[open_manipulator-1]: started with pid [23452]
Joint Dynamixel ID : 11, Model Name : XM430-W350
Joint Dynamixel ID : 12, Model Name : XM430-W350
Joint Dynamixel ID : 13, Model Name : XM430-W350
Joint Dynamixel ID : 14, Model Name : XM430-W350
Gripper Dynamixel ID : 15, Model Name :XM430-W350
[ INFO] [1544509070.096942788]: Succeeded to init /open_manipulator

TIP:

  • If you can’t load DYNAMIXEL, please check your DYNAMIXEL settings using the following command from DYNAMIXEL Workbench packages.
    • U2D2 : $ rosrun dynamixel_workbench_controllers find_dynamixel /dev/ttyUSB0
    • OpenCR : $ rosrun dynamixel_workbench_controllers find_dynamixel /dev/ttyACM0
  • For easy maintanence and configuration of DYNAMIXEL, it is recommended to use DYNAMIXEL Wizard 2.0 or R+ Manager 2.0
  • If you would like to use different DYNAMIXEL ID for OpenMANIPULATOR-X, please modify open_manipulator.cpp in the open_manipulator_lib directory. The default ID is 11, 12, 13, 14 for joints and 15 for the gripper

NOTE:
OpenMANIPULATOR-X controller is compatible with Protocol 2.0.
Protocol 1.0 does not support SyncRead instructions to access multiple DYNAMIXEL simultaneously.
Protocol 2.0 is supported in MX (2.0), X, P, and Pro series only.

Parameter Descriptions

  • use_robot_name : Specifies the name of manipulator (namespace of ROS messages)

  • dynamixel_usb_port : Specifies a USB port. The actual port number assigned to the device may vary by system, but usually the number begins with 0 if there isn’t other device. $ ls /dev/tty* command lists up the ports.
    • Port for U2D2: /dev/ttyUSB0
    • Port for OpenCR: /dev/ttyACM0
  • dynamixel_baud_rate : Specifies baud rate of DYNAMIXEL. The default baud rate is 1000000.

  • control_period : Specifies a communication period (control loop time) between DYNAMIXEL and PC.

  • use_platform : Condition to run the Simulation.
    • Set true when operating the actual OpenMANIPULATOR.
    • Set false when running a virtual OpenMANIPULATOR in Gazebo (3D robotics simulator).
  • use_moveit, planning_group_name, moveit_sample_duration

Open a new terminal and launch the open_manipulator_controller package.

  • When operating with U2D2
    $ roslaunch open_manipulator_controller open_manipulator_controller.launch
    
  • When operating with OpenCR
    $ roslaunch open_manipulator_controller open_manipulator_controller.launch usb_port:=/dev/ttyACM0 baud_rate:=1000000
    

The open_manipulator_controller.launch file has several arguments for launching the controller package. Please see below Parameter Descriptions.

WARNING :
Please check each joint position before running OpenMANIPULATOR-X. The manipulator will not operate if any joint is out of operable range.
The following image describes the recommended pose of OpenMANIPULATOR-X at start up. Please adjust the pose before the torque is turned on by the controller.

Follwing message will be shown in the terminal with a successful launch of the controller.

SUMMARY
========

PARAMETERS
 * /open_manipulator_controller/control_period: 0.01
 * /open_manipulator_controller/using_platform: True
 * /rosdistro: noetic
 * /rosversion: 1.15.9

NODES
  /
    open_manipulator_controller (open_manipulator_controller/open_manipulator_controller)

auto-starting new master
process[master]: started with pid [5454]
ROS_MASTER_URI=http://localhost:11311

setting /run_id to da579122-f0fa-11eb-9d7a-0790f3842b2b
process[rosout-1]: started with pid [5464]
started core service [/rosout]
process[open_manipulator_controller-2]: started with pid [5467]
port_name and baud_rate are set to /dev/ttyUSB0, 1000000 
Joint Dynamixel ID : 11, Model Name : XM430-W350
Joint Dynamixel ID : 12, Model Name : XM430-W350
Joint Dynamixel ID : 13, Model Name : XM430-W350
Joint Dynamixel ID : 14, Model Name : XM430-W350
Gripper Dynamixel ID : 15, Model Name :XM430-W350
[INFO] Succeeded to init /open_manipulator_controller

TIP:

  • If you can’t load DYNAMIXEL, please check your DYNAMIXEL settings using the following command from DYNAMIXEL Workbench packages.
    • U2D2 : $ rosrun dynamixel_workbench_controllers find_dynamixel /dev/ttyUSB0
    • OpenCR : $ rosrun dynamixel_workbench_controllers find_dynamixel /dev/ttyACM0
  • For easy maintanence and configuration of DYNAMIXEL, it is recommended to use DYNAMIXEL Wizard 2.0 or R+ Manager 2.0
  • If you would like to use different DYNAMIXEL ID for OpenMANIPULATOR-X, please modify open_manipulator.cpp in the open_manipulator_lib directory. The default ID is 11, 12, 13, 14 for joints and 15 for the gripper

NOTE:
OpenMANIPULATOR-X controller is compatible with Protocol 2.0.
Protocol 1.0 does not support SyncRead instructions to access multiple DYNAMIXEL simultaneously.
Protocol 2.0 is supported in MX (2.0), X, P, and Pro series only.

Parameter Descriptions

  • usb_port : Specifies a USB port. The actual port number assigned to the device may vary by system, but usually the number begins with 0 if there isn’t other device. $ ls /dev/tty* command lists up the ports.
    • Port for U2D2: /dev/ttyUSB0
    • Port for OpenCR: /dev/ttyACM0
  • baud_rate : Specifies baud rate of DYNAMIXEL. The default baud rate of OpenMANIPULATOR-X is 1000000.

  • control_period : Specifies a communication period (control loop time) between DYNAMIXEL and PC.

  • use_platform : Condition to run the Simulation.
    • Set true when operating the actual OpenMANIPULATOR.
    • Set false when running a virtual OpenMANIPULATOR in Gazebo (3D robotics simulator).

Open a new terminal and launch the open_manipulator_controller package.

  • When operating with U2D2
    $ ros2 launch open_manipulator_x_controller open_manipulator_x_controller.launch.py
    
  • When operating with OpenCR
    $ ros2 launch open_manipulator_x_controller open_manipulator_x_controller.launch.py usb_port:=/dev/ttyACM0
    

WARNING :
Please check each joint position before running OpenMANIPULATOR-X. The manipulator will not operate if any joint is out of operable range.
The following image describes the recommended pose of OpenMANIPULATOR-X at start up. Please adjust the pose before the torque is turned on by the controller.

Follwing message will be shown in the Terminal after the process done successfully with U2D2.

port_name and baud_rate are set to /dev/ttyUSB0, 1000000 
Joint Dynamixel ID : 11, Model Name : XM430-W350
Joint Dynamixel ID : 12, Model Name : XM430-W350
Joint Dynamixel ID : 13, Model Name : XM430-W350
Joint Dynamixel ID : 14, Model Name : XM430-W350
Gripper Dynamixel ID : 15, Model Name :XM430-W350
[INFO] Succeeded to Initialise OpenManipulator-X Controller

TIP:

  • If you can’t load DYNAMIXEL, please check firmware to use ROBOTIS software (R+ Manager 2.0 or DYNAMIXEL Wizard 2.0)
  • If you would like to change DYNAMIXEL ID, please check open_manipulator_x.cpp in the open_manipulator_lib folder. The default ID is 11, 12, 13, 14 for joints and 15 for the gripper

NOTE: OpenMANIPULATOR-X controller is compatible with Protocol 2.0 which supports MX 2.0, X and Pro series. Protocol 1.0 does not support SyncRead instructions to access to multiple DYNAMIXEL’s’s simultaneously.

Open a new terminal and launch the open_manipulator_controller package.

  • When operating with U2D2
    $ ros2 launch open_manipulator_x_controller open_manipulator_x_controller.launch.py
    
  • When operating with OpenCR
    $ ros2 launch open_manipulator_x_controller open_manipulator_x_controller.launch.py usb_port:=/dev/ttyACM0
    

WARNING :
Please check each joint position before running OpenMANIPULATOR-X. The manipulator will not operate if any joint is out of operable range.
The following image describes the recommended pose of OpenMANIPULATOR-X at start up. Please adjust the pose before the torque is turned on by the controller.

Follwing message will be shown in the Terminal after the process done successfully with U2D2.

[INFO] [launch]: All log files can be found below /home/willson/.ros/log/2021-10-07-17-05-57-688562-willson-XPS-15-9560-112659
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [open_manipulator_x_controller-1]: process started with pid [112661]
[open_manipulator_x_controller-1] port_name and baud_rate are set to /dev/ttyUSB0, 1000000 
[open_manipulator_x_controller-1] Joint Dynamixel ID : 11, Model Name : XM430-W350
[open_manipulator_x_controller-1] Joint Dynamixel ID : 12, Model Name : XM430-W350
[open_manipulator_x_controller-1] Joint Dynamixel ID : 13, Model Name : XM430-W350
[open_manipulator_x_controller-1] Joint Dynamixel ID : 14, Model Name : XM430-W350
[open_manipulator_x_controller-1] Gripper Dynamixel ID : 15, Model Name :XM430-W350
[open_manipulator_x_controller-1] [INFO] [1633593958.804918277] [open_manipulator_x_controller]: Succeeded to Initialise OpenManipulator-X Controller

TIP:

  • If you can’t load DYNAMIXEL, please check firmware to use ROBOTIS software (R+ Manager 2.0 or DYNAMIXEL Wizard 2.0)
  • If you would like to change DYNAMIXEL ID, please check open_manipulator_x.cpp in the open_manipulator_lib folder. The default ID is 11, 12, 13, 14 for joints and 15 for the gripper

NOTE: OpenMANIPULATOR-X controller is compatible with Protocol 2.0 which supports MX 2.0, X and Pro series. Protocol 1.0 does not support SyncRead instructions to access to multiple DYNAMIXEL’s’s simultaneously.

  • Arduino sketch for OpenCR OpenMANIPULATOR-X includes the controller in the code.
  • Connecting the OpenMANIPULATOR-X and 12V power source, and turning on the power switch of the OpenCR 1.0 will automatically launch the controller.
  • Please refer to the Launch Controller in the Basic Operation section.