Note: This tutorial assumes that you have completed the previous tutorials: Robots/REEM/Tutorials/Launching a REEM Gazebo simulation, Robots/REEM/Tutorials/play_motion.
(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Use MoveIt! with REEM

Description: This tutorial will show you how to play with Move It ! with the REEM robot

Tutorial Level: BEGINNER

Next Tutorial: Robots/REEM/Tutorials/navigation

Launch MoveIt!

For a kinematic version (very fast) without controllers:

roslaunch reem_moveit_config demo.launch

For a version using the simulated model of REEM:

roslaunch reem_gazebo reem_empty_world.launch
roslaunch reem_moveit_config moveit_rviz.launch config:=true

reem-moveit-kinematic.png

Test Rviz MoveIt! plugin

Go to MotionPlanning (top left) > Planning Request > Planning Group And choose right_arm_torso.

motionplanning-rviz.png

Drag the ball marker on the right arm to a desired pose, adjust orientation with the wheel-like markers. reem-marker-rviz.png

Go to the Planning tab (down left)

1) Click Update (on the Select Start State) to update the initial pose to the current robot pose.

2) Click on Plan to create a plan from current state to the marker pose. You will see an animation of the plan.

3) Click on Execute to send the plan to the controllers so the robot moves. The robot should move to the desired pose following the previewed plan. motion-planning-interface.png

Further information can be found in the MoveIt! tutorials, in particular about the Rviz plugin.

Test MoveIt! via code

You can follow the official MoveIt! Move Group interface tutorials, for Python and for C++.

Also we offer some alternative simple Python examples:

Clone the reem_snippets package from our reem-utils github:

cd ~/reem-sim_ws/src
git clone https://github.com/reem-utils/reem_snippets

The code is very self explanatory with comments all around it.

Now open moveit_pose_goal.py for a pose-based goal:

rosed reem_snippets moveit_pose_goal.py

Or moveit_joints_goal.py for a joint-based goal:

rosed reem_snippets moveit_joints_goal.py

For grabbing joint poses you can use joint_states_group_grabber.py

rosrun reem_snippets joint_states_group_grabber.py -i

Which gives an output like:

[INFO] [WallTime: 1389717404.043611] [1602.174000] Node initialized. Ready to grab joint states.
Interactive mode! Write a group name (or short group name) and it's values will be printed. (Write exit to exit).
['all_joints', 'left_arm', 'right_arm', 'left_arm_torso', 'right_arm_torso', 'torso', 'head', 'right_hand', 'left_hand',
'right_hand_all', 'left_hand_all']
['a', 'la', 'ra', 'lat', 'rat', 't', 'h', 'rh', 'lh', 'rha', 'lha']
> right_arm
Name = Joint Value
=================
arm_right_1_joint = 0.36602641942
arm_right_2_joint = 0.115875053619
arm_right_3_joint = -0.204846821507
arm_right_4_joint = 1.36099376372
arm_right_5_joint = 0.971732788767
arm_right_6_joint = 0.102786035467
arm_right_7_joint = -0.815733486405
right_arm = ['arm_right_1_joint', 'arm_right_2_joint', 'arm_right_3_joint', 'arm_right_4_joint', 'arm_right_5_joint',
'arm_right_6_joint', 'arm_right_7_joint']
[ 0.36602641942, 0.115875053619, -0.204846821507, 1.36099376372, 0.971732788767, 0.102786035467,
-0.815733486405 ]

Which can be copy-pasted in a Python file as lists.

Wiki: Robots/REEM/Tutorials/moveit (last edited 2014-05-15 11:04:04 by SamPfeiffer)