$ catkin create pkg iiwa_14_r820_robot_moveit_client --catkin-deps moveit_commander rospy
$ catkin build 
$ source ~/.bashrc

데모 실행 전에, 로봇을 bringup하고, move_group을 실행

$ roslaunch iiwa_14_r820_robot_bringup bringup.launch
$ roslaunch iiwa_14_r820_robot_moveit_config move_group.launch

데모1: 설정 정보 가져오기

src/d1_get_info.py

#!/usr/bin/env python

import sys
import rospy
import moveit_commander

if __name__ == "__main__":
    # Initialize moveit_commander and node
    moveit_commander.roscpp_initialize(sys.argv)
    rospy.init_node('d1_get_basic_info', anonymous=False)

    # Get instance from moveit_commander
    robot = moveit_commander.RobotCommander()
    scene = moveit_commander.PlanningSceneInterface()

    # Get group_commander from MoveGroupCommander
    group_name = "arm"
    move_group = moveit_commander.MoveGroupCommander(group_name)

    # Get information
    planning_frame = move_group.get_planning_frame()
    eef_link = move_group.get_end_effector_link()
    group_names = robot.get_group_names()
    current_state = robot.get_current_state()

    print "============ Planning frame: %s" % planning_frame
    print "============ End effector link: %s" % eef_link
    print "============ Available Planning Groups:", robot.get_group_names()
    print "============ Printing robot state"
    print current_state
    print "="*20

    quit()

.py 파일에 실행 옵션을 추가한다.

$ roscd iiwa_14_r820_robot_moveit_client/src/
$ chmod +x d1_get_info.py
$ rosrun iiwa_14_r820_robot_moveit_client d1_get_info.py

데모2: End Effector Link를 원하는 지점으로 이동하기

src/d2_move_target_pose.py

#!/usr/bin/env python

import sys
import copy
import rospy
import moveit_commander
import geometry_msgs.msg
from math import pi
from tf.transformations import *

if __name__ == "__main__":
    # Initialize moveit_commander and node
    moveit_commander.roscpp_initialize(sys.argv)
    rospy.init_node('d2_move_target_pose', anonymous=False)

    # Get instance from moveit_commander
    robot = moveit_commander.RobotCommander()
    scene = moveit_commander.PlanningSceneInterface()

    # Get group_commander from MoveGroupCommander
    group_name = "arm"
    move_group = moveit_commander.MoveGroupCommander(group_name)

    # Move using target_pose
    pose_goal = geometry_msgs.msg.Pose()

    pose_goal.position.x = 0.0
    pose_goal.position.y = -0.6
    pose_goal.position.z = 0.8

    quat = quaternion_from_euler(pi/2.0, -pi/2.0, 0.0)

    pose_goal.orientation.x = quat[0]
    pose_goal.orientation.y = quat[1]
    pose_goal.orientation.z = quat[2]
    pose_goal.orientation.w = quat[3]

    move_group.set_pose_target(pose_goal)

    plan = move_group.go(wait=True)
    move_group.stop()
    move_group.clear_pose_targets()

    quit()

데모3: 조인트 명령으로 이동하기.