Yaskawa Motoman
- This page describes the initial run of Yaskawa Motoman robot from ROS.
Reference †
- ROS industrial: http://wiki.ros.org/Industrial
- motoman: http://wiki.ros.org/motoman
- motoman/Tutorials: http://wiki.ros.org/motoman/Tutorials
- motoman_driver: http://wiki.ros.org/motoman_driver
- motoman_driverTutorials: http://wiki.ros.org/motoman_driver/Tutorials
General Information †
The following is the information of our Motoman system.
Control PC:
- OS: NAME="Ubuntu" VERSION="14.04.5 LTS, Trusty Tahr" (Ubuntu 16 is also installed as dual boot)
- ROS: Indigo
- eth0: a0:36:9f:e3:fb:8e
- eth1: a0:36:9f:e3:fb:8f (for Motoman)
- eth2: 70:85:c2:2e:e0:cd (for LAN)
Motoman:
- Type: YR-SIA010F-A00
- Control box: FS100
Motoman network config:
- Control PC: 192.168.12.30, eth1/a0:36:9f:e3:fb:8f
- FS100: 192.168.12.31, 00:20:b5:2b:2c:6f
- Pendant: 192.168.12.32, 00:20:b5:35:d9:01
Tip: how to get the MAC address from an IP?
$ ping 192.168.12.31 $ pint 192.168.12.32 $ arp -a ? (192.168.12.32) at 00:20:b5:35:d9:01 [ether] on eth1 ? (192.168.12.31) at 00:20:b5:2b:2c:6f [ether] on eth1
Installation †
Follow the installation guide of ROS industrial:
What I did:
- Typically install ROS "Desktop Full" of indigo (or other LTS).
- Industrial core:
Or$ sudo apt-get install ros-indigo-industrial-core
$ sudo apt-get install ros-kinetic-industrial-core
- Motoman stack:
- From binary package:
$ apt-get install ros-indigo-motoman
- From source (recommended):
$ cd catkin_ws/src/ $ git clone https://github.com/ros-industrial/motoman.git $ cd .. $ catkin_make
- From binary package:
Install Motoman ROS server (MotoROS Driver) on FS100.
- http://wiki.ros.org/motoman_driver/Tutorials/indigo/InstallServer
- Download MotoRosFS100.out and install it on FS100.
- Install INFORM Code.
Usage †
Using the Motoman FS/DX ROS Interface:
http://wiki.ros.org/motoman_driver/Tutorials/Usage
Preparation of Pendant:
- Pendant key switch must be in Remote mode.
- The E-stop latch must be released.
Setup:
- ROS_MASTER_URI=http://localhost:11311
Note: the ROS master is Control PC.
Test run:
$ roslaunch motoman_driver robot_interface_streaming_fs100.launch robot_ip:=192.168.12.31
$ rostopic echo /joint_states
Note: You will see 6 joints only.
Standard run:
$ roscore
($ rosparam load /opt/ros/indigo/share/motoman_sia10f_support/urdf/sia10f.urdf robot_description)
$ rosparam load `rospack find motoman_sia10f_support`/urdf/sia10f.urdf robot_description
$ rosparam set controller_joint_names "[joint_s, joint_l, joint_e, joint_u, joint_r, joint_b, joint_t]"
$ roslaunch motoman_driver robot_interface_streaming_fs100.launch robot_ip:=192.168.12.31
$ rosrun robot_state_publisher robot_state_publisher
$ rviz
$ rostopic echo /joint_states
Now you will see a sequence of ['joint_s', 'joint_1', 'joint_2', 'joint_3', 'joint_4', 'joint_5', 'joint_6'].
See 2.1 Joint Naming of http://wiki.ros.org/motoman_driver/Tutorials/Usage to change the order of joint names in /joint_states.
Test motion (BE CAREFUL! ROBOT MOVES!!):
$ rosservice call /robot_enable
$ rosrun motoman_driver move_to_joint.py "[0.21, -0.59, 0.30, -1.46, 0.35, -0.68, 0.31]" 5.0
$ rosservice call /robot_disable
To initial pose:
$ rosrun motoman_driver move_to_joint.py "[0, 0, 0, 0, 0, 0, 0]" 5.0
How to program robot motion? †
Let's understand move_to_joint.py:
- A motion is designed as a joint-angle trajectory (JointTrajectory message is used).
- JointTrajectory is published to joint_path_command topic.
How to simulate kinematic motions? -- Ver.1 †
We can simulate the robot dynamics with Gazebo but it is computationally expensive. If we want to check only the kinematic motion or configuration of robot, we can do that (simply) with RViz.
The idea is that loading robot model parameters (URDF), sending virtual joint angle data to /joint_states topic, and running robot_state_publisher that computes TF.
More concretely,
$ roscore
$ rosparam load `rospack find motoman_sia10f_support`/urdf/sia10f.urdf robot_description
$ rosparam set controller_joint_names "[joint_s, joint_l, joint_e, joint_u, joint_r, joint_b, joint_t]"
$ rosrun robot_state_publisher robot_state_publisher
$ ./dummy_joint_states.py
$ rviz
Note that we don't run motoman_driver. The point is dummy_joint_states.py which send messages to /joint_states topic. An example of the implementation is: https://github.com/akihikoy/motoman_test/blob/master/dummy_joint_states.py
How to simulate kinematic motions? -- Ver.2 †
Based on the above idea, we can create a node that receives the joint_path_command topic and sends messages to the joint_states topic so that the virtual motoman behaves like a real robot.
Benefit: We can operate the virtual Motoman similar to the real robot.
How to do that?
Instead of running motoman_driver, execute dummy_moto2.py
https://github.com/akihikoy/motoman_test/blob/master/dummy_moto2.py
Then you can send a command like:
$ rosrun motoman_driver move_to_joint.py "[0.21, -0.59, 0.30, -1.46, 0.35, -0.68, 0.31]" 5.0
or you can also write your own program to control the robot, for example:
https://github.com/akihikoy/motoman_test/blob/master/follow_q_traj1.py
Next step †
http://wiki.ros.org/motoman/Tutorials/Path_Planning_with_Arm_Warehouse_Viewer
Issues †
Cannot observe joint velocity and effort †
See: https://answers.ros.org/question/276723/motoman-fs100-missing-velocity-and-effort-in-joint_states/
Cannot change current trajectory †
If we try, trajectory controller fails with a message:
[ERROR] [1511763099.994990242]: Validation failed: Trajectory doesn't start at current position. [ERROR] [1511763099.738602894]: Aborting Trajectory. Failed to send point (#0): Invalid message (3) : Trajectory start position doesn't match current robot position (3011)
Cannot implement feedback control †
If we try, trajectory controller fails with a message:
[ERROR] [1511763103.152466393]: Trajectory splicing not yet implemented, stopping current motion.
Cf. https://github.com/ros-industrial/industrial_core/issues/154
See: https://answers.ros.org/question/277091/motoman-fs100-velocity-feedback-control/
More error info:
[ERROR] [1511841339.366407562]: Aborting Trajectory. Failed to send point (#0): Invalid message (3) : Trajectory start position doesn't match current robot position (3011) [ERROR] [1511841339.621870698]: Trajectory splicing not yet implemented, stopping current motion. [ERROR] [1511841339.622553123]: Validation failed: Trajectory doesn't start at current position. [ERROR] [1511841339.622703323]: Validation failed: Trajectory doesn't start at current position. [ERROR] [1511841339.622868904]: Validation failed: Trajectory doesn't start at current position. [ERROR] [1511841339.623028727]: Validation failed: Trajectory doesn't start at current position. [ERROR] [1511841339.623588373]: Trajectory splicing not yet implemented, stopping current motion. [ERROR] [1511841339.624581918]: Trajectory splicing not yet implemented, stopping current motion. [ERROR] [1511841339.877039250]: Trajectory splicing not yet implemented, stopping current motion. [ERROR] [1511841339.877992911]: Trajectory splicing not yet implemented, stopping current motion. [ERROR] [1511841339.878956057]: Trajectory splicing not yet implemented, stopping current motion. [ERROR] [1511841339.879945824]: Trajectory splicing not yet implemented, stopping current motion. [ERROR] [1511841339.880982802]: Trajectory splicing not yet implemented, stopping current motion. [ERROR] [1511841340.148480496]: Trajectory splicing not yet implemented, stopping current motion.