Author: Jordi Pages < jordi.pages@pal-robotics.com >
Maintainer: Sara Cooper < sara.cooper@pal-robotics.com >
Support: ari-support@pal-robotics.com
Source: https://github.com/pal-robotics/ari_tutorials.git
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. |
Playing pre-defined upper body motions
Description: Tutorial on how to play back pre-defined upper body motions with ARI using the play_motion package.Keywords: play_motion, joint_trajectory_controller, motion planning
Tutorial Level:
Contents
Purpose
The purpose of this tutorials is to show how to run pre-defined upper body motions with ARI. This is pretty easy by using the play_motion package, which enables executing simultaneous trajectories in multiple groups of joints.
Pre-requisites
First make sure that the tutorials are properly installed along with the ARI simulation, as shown in the Tutorials Installation Section.
Execution
First open two consoles and source the public simulation workspace as follows:
$ cd ~/ari_public_ws $ source ./devel/setup.bash
Launching the simulation
In the first console launch for example the following simulation
roslaunch ari_gazebo ari_gazebo.launch public_sim:=true world:=empty
Gazebo will show up with ARI in an empty world.
When the simulation is launched, the play_motion action server is automatically launched and the motions defined in ari_bringup/config/ari_motions.yaml have been loaded in the ros parameter server.
In order to see the names of the motions defined run the following instruction in the second console:
$ rosparam list | grep "play_motion/motions" | grep "meta/name" | cut -d '/' -f 4
The following motions are available in the public simulation:
bow look_around nod shake_left shake_right show_left show_right start_ari wave
The relevant information of a motion, i.e. the wave motion, is stored in the following parameters:
/play_motion/motions/wave/joints /play_motion/motions/wave/points
In the case of the wave motion the joints parameter specifies which joints intervene in the motion:
$ rosparam get /play_motion/motions/bow/joints [arm_left_1_joint, arm_left_2_joint, arm_left_3_joint, arm_left_4_joint, arm_right_1_joint, arm_right_2_joint, arm_right_3_joint, arm_right_4_joint, head_1_joint, head_2_joint]
which denotes that in order to execute this motion the group of joints of the arm will be used.
The joint trajectory, i.e. timed sequence of positions (see http://wiki.ros.org/joint_trajectory_controller for details), that composes this motion can be retrieved as follows
$ rosparam get /play_motion/motions/bow/points - positions: [-0.201, 0.0488, 0.0372, 0.4028,-0.2014, 0.0485, 0.0462, 0.404, 0, -0.0078] time_from_start: 0.0 - positions: [-0.403, 0.0494, 0.0365, 0.2869, -0.4006, 0.0495, 0.0496, 0.3064, -0.0001, 0.2957] time_from_start: 2.0 - positions: [-0.403, 0.0494, 0.0365, 0.2869, -0.4006, 0.0495, 0.0496, 0.3064, -0.0001, 0.2957] time_from_start: 2.5 - positions: [-0.201, 0.0488, 0.0372, 0.4028, -0.2014, 0.0485, 0.0462, 0.404, 0, -0.0078] time_from_start: 3.5
Each row of positions denote the position that each joint has to attain at the given time with respect to the start of the motion.
Playing motions
As said, the play_motion is an action server. In order to run a motion the following graphical action client can be used
$ rosrun actionlib axclient.py /play_motion
In the GUI the name of the motion to run must be filled. The skip_planning is set by default to False, which means that the transition to the first position of the joint trajectory will use planning to prevent collisions. The remaining of the trajectory is always executed without planning as it is responsibility of the programmer to define a safe trajectory. Set skip_planning to True only if you are sure that it is safe to reach the first positions in the trajectory from the current kinematic configuration of the robot.
By pressing the SEND GOAL button the request will be sent to /play_motion Action Server and the motion will start executing as shown in the pictures.
|
|
|
|
C++ and Python action clients
In ari_tutorials/run_motion there are play_motion action clients in C++ and Python.
The usage of the C++ action client node is as follows
rosrun play_motion run_motion wave
where the argument is the name of the motion. If no motion is given the list of available motions will be printed out.
The Python action client node is run as follows
rosrun play_motion run_motion_python_node.py home