Skip to content

Trigger user messages in drag&bot

User messages are a possibility in drag&bot to give the user short information in a permanent or temporary way. This can e.g. a information message, that some component is in a specific noticeable state.

Example Toast Message

Interface

Toast messages can be triggered by the Function Block "User Message" or from a ROS interface. The messages are shown infinitely or for a configurable amount of time before they disappear. Also, it can be determined, whether the user can acknowledge the message manually or not. The type of the message, indicated by the color, can be configured as well as an ID for the sender. The ID is necessary to identify the message internally and in case the message should be removed later by service call.

A toast message can be triggered via ROS by calling the service /human_interaction/request_user_info of type human_interaction/RequestUserInfo.

The interface of the service human_interaction/RequestUserInfo is defined as follows:

Request:

UserInformation user_info
    # Contains all parameters for the shown information.

Response:

-

The interface of the message human_interaction/UserInformation is defined as follows:

int32 type
    # Available type values are:
    #  UserInformation.INFO=0 (blue)
    #  UserInformation.SUCCESS=1 (green)
    #  UserInformation.WARNING=2 (yellow)
    #  UserInformation.ERROR=3 (red)

string message
    # Message to show to the user.

int32 show_until
    # >0: The timestamp until when the information is shown.
    # =0: The message is shown infinitely until it is closed manually 
    #       by the user or by service.

string id
    # Unique id to identify the message internally 
    #  and for manual closing by service.

bool hide_close_button
    # Option to hide the close button for the user. 
    # If active and the message is shown infinitely, 
    #  the message can only be removed by another service call
    #  of service "/human_interaction/info_close".

To close a previously created message, the service /human_interaction/info_close of type human_interaction/HumanAnswer can be used.

Request:

string uuid
    # Used id of the message, which should be closed.

string option
    # Not used in this context.

Response:

bool ok
    # Indicates, whether the message was successfully closed.

Example 1

The example creates a user info message, which is automatically closed after 10 seconds. The user can close the message manually.

#!/usr/bin/python3
import rospy
import time
import uuid

from human_interaction.msg import UserInformation
from human_interaction.srv import RequestUserInfo, RequestUserInfoRequest, RequestUserInfoResponse

if __name__ == "__main__":

    rospy.init_node('user_message_service_example_node')

    rospy.wait_for_service('human_interaction/request_user_info', 1.0)  
    srv = rospy.ServiceProxy('human_interaction/request_user_info', RequestUserInfo)

    rospy.sleep(1)

    request = RequestUserInfoRequest()

    # available types are: 
    #  UserInformation.INFO=0
    #  UserInformation.SUCCESS=1
    #  UserInformation.WARNING=2
    #  UserInformation.ERROR=3
    request.user_info.type = UserInformation.INFO

    request.user_info.message = "This is an example message."

    # show the message until 10 seconds after execution
    request.user_info.show_until = int(time.time()) + 10

    # unique id to identify the message
    request.user_info.id = str(uuid.uuid4())

    # don't hide the close button to the user
    request.user_info.hide_close_button = False

    response = srv.call(request)

Example 2

The example creates a user warning message, which is shown infinitely. The user can't close the message manually. The message is closed by service 10 seconds after it was created.

#!/usr/bin/python3
import rospy
import time
import uuid

from human_interaction.msg import UserInformation
from human_interaction.srv import RequestUserInfo, RequestUserInfoRequest, RequestUserInfoResponse
from human_interaction.srv import HumanAnswer, HumanAnswerRequest, HumanAnswerResponse

if __name__ == "__main__":

    rospy.init_node('user_message_service_example_node')

    rospy.wait_for_service('/human_interaction/request_user_info', 1.0) 
    srv = rospy.ServiceProxy('/human_interaction/request_user_info', RequestUserInfo)

    rospy.sleep(1)

    request1 = RequestUserInfoRequest()

    # available types are:
    #  UserInformation.INFO=0 (blue)
    #  UserInformation.SUCCESS=1 (green)
    #  UserInformation.WARNING=2 (yellow)
    #  UserInformation.ERROR=3 (reds)
    request1.user_info.type = UserInformation.WARNING

    request1.user_info.message = "This is an example message."

    # show the message until it is closed manually or by service
    request1.user_info.show_until = 0

    # unique id to identify the message
    request1.user_info.id = str(uuid.uuid4())

    # hide the close button from the user
    request1.user_info.hide_close_button = True

    response1 = srv.call(request1)

    # wait for 10 seconds

    rospy.sleep(10)

    # after 10 seconds remove the message by service

    rospy.wait_for_service('/human_interaction/info_close', 1.0)    
    srv = rospy.ServiceProxy('/human_interaction/info_close', HumanAnswer)

    request2 = HumanAnswerRequest()

    # the same id as set for the first request has to be set here
    # to close the correct message
    request2.uuid = request1.user_info.id

    response2 = srv.call(request2)