Tutorial: Creating a simple multi-modal interaction#
🏁 Goal of this tutorial
By the end of this tutorial, you will be able to create an example of a multi-modal interaction using voice, motions, and face detection, utilizing the structure provided by
pal_app
.
Create an app using pal_app
#
Create on your computer a development workspace (that we will mount in the SDK Docker image):
> mkdir ~/ws
Start the SDK Docker image (replacing
customer_id
by your own PAL-provided customer ID):
> docker run -it $HOME/ws:/home/pal/ws registry.gitlab.com/pal-robotics/customer_id/dockers:latest bash
Create a new app skeleton:
> cd ws
> mkdir src && cd src
> pal_app create
You can for instance use first_app
as app ID, and My First App
as app
name.
Multi-modal interaction:#
The pal_app
structure revolves around handling Intents. In this
tutorial, we will create the multi-modal interaction by defining a callback
function that gets executed whenever a face is detected.
Note
Intents are an abstract description (a ROS message) representing something that someone wants the robot to perform. Intents are usually published by the user-perception nodes (like the dialogue manager, or the touchscreen manager), and are processed by the application controller.
We will use the pyhri
library to detect faces. Once a face is detected,
the robot will greet the person and perform a gesture.
First, we initialize the HRIListener
, TransformListener
, and
look_at
publisher in the run()
function.
The last thing is to initialize the on_face()
function an create the
callback function that will run when a face is detected:
listener = HRIListener()
tf_listener = tf.TransformListener()
look_at_pub = rospy.Publisher("/look_at", PointStamped, queue_size=10)
listener.on_face(face_cb)
If the attention manager
is running on the robot, we need to stop it.
Here is an example of how to do it through a script:
rospy.wait_for_service('attention_manager/set_policy')
serv = rospy.ServiceProxy('attention_manager/set_policy', SetPolicy)
try:
serv(policy=0)
except rospy.ServiceException as exc:
print("Service did not process request: " + str(exc))
We need to stop the attention_manager
because otherwise the robot will not
reach the point we will send through the /look_at
topic.
The callback function face_cb()
handles the detected face.
def face_cb(face):
points = PointStamped()
points = tf_listener.lookupTransform("face_%s" % face,
"head_front_camera_link",
rospy.Time())
look_at_pub.publish(points)
tts = actionlib.SimpleActionClient('tts', TtsAction)
play_motion = actionlib.SimpleActionClient('play_motion', PlayMotionAction)
tts_goal = TtsGoal()
tts_goal.rawtext.text = "Hello, I'm ARI. Nice to meet you!"
tts_goal.rawtext.lang_id = "en_GB"
tts.send_goal_and_wait(tts_goal)
motion_goal = PlayMotionGoal(motion_name="wave")
play_motion.send_goal_and_wait(motion_goal)
It retrieves the face’s location using the lookupTransform()
function and publishes the point on the /look_at
topic. It also uses
the TTS action
to greet the person and the play_motion
action to
perform a waving motion.
Deploy the app on the robot:#
To install the app you have created on the robot, you need to follow the next steps:
From inside your SDK Docker image, go to your development workspace:
> cd ~/ws
Then run:
> rosrun pal_deploy deploy.py --package first_app ari-XXc
(Replace ari-XXc
by your actual robot)
With the code deployed, you can now ssh
onto the robot (
ssh pal@ari-XXc
, password: pal
) and navigate to your project:
cd ~/deployed_ws/share/first_app
.
For a more detailed explanation of the deployment process, refer to: Tutorial: Deploying ROS packages on the robot
Run the app in the robot:#
To run the app, ssh
onto the robot (ssh pal@ari-XXc
, password: pal
) and start your application: rosrun first_app run_app
.
See also:#
Create an application with pal_app for a detailed understanding of the
pal_app
structure.