../_images/tiago-icon.png ../_images/tiagopro-icon.png ../_images/ari-icon.png

Controlling the attention and gaze of the robot#

The robot’s gaze is controlled by several nodes, visible in the following diagram.

image/svg+xml attention manager /look_at gaze manager /robot_face/look_at expressive eyes tf:/current_gaze_target head controller /head_controller/point_head_action rtt deployer /head_controller/follow_joint_trajectory

Attention management#

The attention_manager node is responsible for the high-level control of the robot attention. This behaviour is driven by attention policies that you can change via the /attention_manager/set_policy ROS service.

As of pal-sdk-23.12, the following policies are available:

  • DISABLED (0): the attention manager does not control the robot’s focus of attention

  • RANDOM (1): randomly look around, with short fixations

  • IDLE_SOCIAL (2): the robot looks around for faces, with fixations on detected faces.

  • FOCUSED_SOCIAL (3): focus the robot’s attention on a specific frame (typically, a person), provided as the frame parameter when invoking the service. If no frame parameter is provided, the attention manager focuses on the last tracked frame (if any).

At startup, the attention manager defaults to the IDLE_SOCIAL policy.

Important

If you want to control yourself the gaze direction of the robot (see below), you need to disable the attention manager first, by calling the /attention_manager/set_policy ROS service with the policy DISABLED.

Gaze manager#

Overview#

The gaze_manager role is to coordinate the robot’s eyes with the neck. It listens to stamped points (geometry_msgs/PointStamped) published to the /look_at topic, and direct the robot’s gaze to these points.

In order to generate a natural-looking gaze behaviour, the gaze manager first instruct the eyes to look at the target (by re-publishing the stamped point to the /robot_face/look_at topic).

Then, the eyes manager publishes a TF frame called /current_gaze_target corresponding to where the eyes are currently looking at.

Finally, the gaze manager monitors this frame, and sends accordingly goals to the head controller, which transforms the cartesian look at target into a trajectory in joint space.

How to set the gaze direction?#

You can set the robot’s gaze direction by publishing any 3D stamped point to the /look_at topic:

Set the gaze direction#
 1import rospy
 2from geometry_msgs.msg import PointStamped
 3
 4
 5rospy.init_node("gaze_controller_example")
 6
 7pub = rospy.Publisher("/look_at", PointStamped, queue_size=10)
 8
 9target = PointStamped()
10
11# look at a point located 1.5m above, and 2m left of the world origin
12# This point will be tracked by the robot, even when it moves around.
13target.header.frame_id = "map"
14target.point.x = 0.
15target.point.y = -2.
16target.point.z = 1.5
17
18pub.publish(target)

Important

The robot will track this point until a new point is published, or a call to /gaze_manager/reset_gaze is performed.

If you want the robot to completely stop tracking any point, you can publish the point 10,0,0 in the /sellion_link frame (ie, the frame of the eyes): you would be asking the robot to always look in front of its eyes, which is by definition always the case.

$ rostopic pub /look_at geometry_msgs/PointStamped "header:
    seq: 0
    stamp:
        secs: 0
        nsecs: 0
    frame_id: '/sellion_link'
    point:
    x: 10.0
    y: 0.0
    z: 0.0"

Controlling only the eyes#

It is sometimes desirable to only control the eyes, without moving the head itself (for instance, if you want to keep the head facing a certain direction, or control the head motion with another mechanism, like Re-play motions.

You can explicitely disable or enable the control of the neck with the /gaze_manager/disable_neck and /gaze_manager/enable_neck

See also#