How-to: Control ARI’s expressions#
Both the expression and the position of ARI’s eyes can be controlled via ROS.
Note
Currently, the eyes can only be controlled through a ROS interface. In future releases of the SDK, alternative no-code solutions will be offered.
Expressions#

The expression of the eyes can be changed via the /robot_face/expression topic.
You can either use one of the pre-defined expressions (like happy, confused… see list below), or by setting a custom values for valence and arousal, following the circumplex model of emotions.
Code samples#
The following short snippet of Python code loops over several expressions, as show in the animation above:
1import rospy
2from hri_msgs.msg import Expression
3
4if __name__ == "__main__":
5
6 rospy.init_node("publisher")
7 pub = rospy.Publisher("/robot_face/expression", Expression, queue_size=10)
8
9 msg = Expression()
10 expressions = ["happy", "confused", "angry", "sad", "amazed", "rejected"]
11
12 rate = rospy.Rate(1) # 1Hz
13 idx = 0
14
15 while not rospy.is_shutdown():
16 msg.expression = expressions[idx % len(expressions)]
17 pub.publish(msg)
18
19 idx += 1
20 rate.sleep()
This second example changes the expression continuously, by increasing/decreasing the valence and arousal:
1import rospy
2from hri_msgs.msg import Expression
3
4if __name__ == "__main__":
5
6 rospy.init_node("publisher")
7 pub = rospy.Publisher("/robot_face/expression", Expression, queue_size=10)
8
9 msg = Expression()
10
11 rate = rospy.Rate(5)
12
13 valence = 0.
14 arousal = 0.
15 valence_delta = 0.05
16 arousal_delta = 0.0
17
18 while not rospy.is_shutdown():
19 msg.valence = valence
20 msg.arousal = arousal
21
22 valence += valence_delta
23 arousal += arousal_delta
24
25 if valence > 1:
26 valence = 1
27 valence_delta = 0.
28 arousal_delta = 0.05
29 if arousal > 1:
30 arousal = 1
31 valence_delta = -0.05
32 arousal_delta = 0.0
33 if valence < -1:
34 valence = -1
35 valence_delta = 0.0
36 arousal_delta = -0.05
37 if arousal < -1:
38 arousal = -1
39 valence_delta = 0.05
40 arousal_delta = 0.0
41
42 print("Valence: %.1f; arousal: %.1f" % (valence, arousal))
43 pub.publish(msg)
44
45 rate.sleep()
List of expressions#
The hri_msgs/Expression ROS message lists all pre-defined expression. The table below shows how these expressions are rendered on the robot.
Expression name |
Appearance |
Expression name |
Appearance |
---|---|---|---|
|
![]() |
|
![]() |
|
![]() |
|
![]() |
|
![]() |
|
![]() |
|
![]() |
|
![]() |
|
![]() |
|
![]() |
|
![]() |
|
![]() |
|
![]() |
|
![]() |
|
![]() |
|
![]() |
|
![]() |
|
![]() |
|
![]() |
|
![]() |
|
![]() |
|
![]() |
|
![]() |
|
![]() |
|
![]() |
Gaze direction#
The Controlling the attention and gaze of the robot page contains all the details regarding how to control the robot’s gaze and attention.