Main Engine and Parsing Unit - RoBorregos/robocup-home GitHub Wiki

Overview

The main engine is in charge of administering the tasks performed by the robot. This involves contacting the action servers exposed by the navigation stack, object detection module, and the arm component. When monitoring the tasks, the main engine is responsible for the interactions between the tasks performed, the current state of the tasks, and giving feedback to the user if an error is triggered or a task is skipped. A new task is triggered via the parser when the user submits a voice command.

Reading this page

Italics will be used when talking about a file, script, or package found in the repository Bold will be used when talking about a function, class, or component found in the code.

Tech used

Python 2.17, actionlib, RASA

Parsing Unit components

  • action_selectors/parser.py
  • rasa

RASA

For intent classification, entity extraction, and conversation tracking the RASA framework is being used.

First, some definitions:

  • intent: What the user means with the sentence given. Ex: Please be quiet (intent: Shut up)
  • entities: Relevant pieces of information given in the sentence. Ex: Ah man, a burger would be awesome right now

To add a new intent for the RASA unit three steps must be performed:

  1. Add intent examples in the data.nlu file.
  2. Add story examples in the stories.nlu file.
  3. Re-train the model with the new data.

The RASA endpoint is located in this url.

parser

The parser receives a string from the Speech to Text (STT) module and outputs the intent of the user and arguments. The possible_actions.csv file has the domain of actions known by the robot. Every time new functionality is added to the robot it must be updated this file to add it. The fields found in the CSV are the following:

cmd_id cmd_category cmd_priority requires_args action_client
name of the action number of the category priority (0 biggest, 999 lowest) True/False Nam of the action client

The call to the RASA unit is done in the call RASA function:

def callRASA(self, text):
        global response
        intent = ""
        args = [""]
        # make request to rasa server
        command = text
        # Publish to Vizbox
        # instantiate response msg object
        response_to_publish = String()
        # evaluate
        self.say("You just said:" + command)
        data = {"sender": "home",
                "message": command}
        responseHTTP = requests.post(
            "http://localhost:5005/webhooks/rest/webhook", json=data)
        nlu_response = requests.post(
            "http://localhost:5005/model/parse", json={"text": data["message"]})
        if(responseHTTP.status_code == 200 and nlu_response.status_code == 200):
            if(len(responseHTTP.json()) > 0):
                for responseData in responseHTTP.json():
                    self.debug("BOT SAYS: " + responseData["text"])
                    response_to_publish.data = responseData["text"]
                    self.pub_resp.publish(response_to_publish)
                    nlu_info = nlu_response.json()
                    if(nlu_info["intent"]["confidence"]>=0.60):
                        self.debug(nlu_info["intent"])
                        intent = nlu_info["intent"]["name"]
                        args = nlu_info["entities"]
                        self.debug("Entities: " + str(nlu_info["entities"]))
        else:
            response_to_publish.data = "Cant connect to RASA server"
            self.pub_resp.publish(response_to_publish)
            self.debug("Failed response")
        return intent, args

All current actions are limited to one type of argument, but multiple values can be provided. For example, the intent pick_up_object can only be provided arguments of the type object but multiple objects can be given as values.

Pick up the apple and soda please, Mr. Robot

The only exception to the rule above, as of right now, is the intent bring_something which involves both the place and object types of arguments. To handle this edge case, a new concept was introduced into the design structure: meta_actions.

Meta_actions

A meta_action is defined as an action that encapsulates several base actions to be completed. The best example for this concept is bring_something which actually involves go_to, approach, center, pick_up and go_to actions to be completed. To achieve this, the function to publish the actions involved in bring something was introduced:

def publish_bring_something(self, intent, args):
        target_location = ""
        target_object = ""
        story = Story()
        story.title = "Bring Something"
        story.storyline = []
        for entity in args:
            if(entity.get("entity") == 'object'):
                target_object = entity.get("value")
            elif(entity.get("entity") == 'place'):
                target_location = entity.get("value")
        actions_needed = ["go_to", target_location], ["approach", target_object],["center",target_object],["pick_up",target_object],["go_to","original_location"](/RoBorregos/robocup-home/wiki/"go_to",-target_location],-["approach",-target_object],["center",target_object],["pick_up",target_object],["go_to","original_location")
        for action in actions_needed:
            arg = ""
            action_request= action_selector_cmd()
            action_request.intent= action[0]
            if(len(action)>1):
                arg = action[1]
            action_request.args= arg
            action_request.action_client_binded= self.possible_actions[action[0]]['action_client_binded']
            rospy.loginfo(action_request)
            story.storyline.append(action_request.intent + " : " + action_request.args)
            self.pub.publish(action_request)
            print(self.possible_actions[intent])
        self.pub_story.publish(story)

Main Engine components

  • main_engine/action_manager.py
  • main_engine/Action class

action_manager

The action manager receives an action message defined in the intercom.action_selector_cmd file with the following structure:

Header header
string intent
string action_client_binded
string args 

When the message is received a new action is created (see Action class), and added to the queue:

new_action = Action(msg.intent,
                            msg.action_client_binded, msg.args)
        self.lastActionReceived = new_action       
        ##Stop Action
        if(new_action.id=="stop"):
            self.stop_everything()
            return
        if(len(self.action_queue)==0):
            self.trigger_new_action(new_action)
        #Add it to the queue (doesn't matter if it was triggered or not)
        self.action_queue.append(new_action)

The only exception is the stop action which is immediately triggered with absolute priority over anything else, to ensure the safety of the users interacting with the robot.

When a new action is added to the queue the current action running is not preempted. When an action reaches the first spot in the queue (or if the queue was empty before it entered) it gets triggered. This means:

  1. Creating a new action client.
  2. Deleting the previous action from the queue and add it to history[].
  3. Sending the Goal to the action server.
  4. Keep it running until a SUCCEEDED, ABORTED, or LOST state is reached.

When an action is running it is constantly being monitored in the monitor function.

Action class

The constructor of the class receives the following parameters:

def __init__(self, id, action_client_binded, args)

In this class, there are generic functions related to logging, updating, and getting feedback for all the actions in the robot. A specific implementation of the actions is implemented in classes that inherit from this base class. To implement the execution part of the action, the method def run() must be overloaded in the child classes. For example, the following code corresponds to the run() method of the pick_up class:

  def run(self):
        print("Setting goal,filling it and contacting action server of pick_up")
        ArmAction = rb_home_arm.msg.ArmAction
        self.run_action_client(ArmAction)
        print("Done initial contact with server")
        goal = rb_home_arm.msg.ArmGoal()
        goal.object = self.args
        goal.type_of_movement = "pick_up"
        self.action_client.send_goal(goal)

The base Action class also exposes the state of the action for the action_manager. According to ROS, this state can take one of the following values:

 ["PENDING", "ACTIVE", "RECALLED","REJECTED", "PREEMPTED", "ABORTED", "SUCCEEDED", "LOST"]

When an action is first introduced into the action queue it has a state of PENDING. And when the action runs its state changes to ACTIVE. In the happy path, the action will reach SUCCEEDED, but error states can also be reached like LOST or ABORTED. The action server is in charge of updating this state accordingly.

Installation Requirements

NA

Additional modifications and improvements

  • MultiQueue Actions.
  • Improved change of STATE of actions.
  • Error handling.

Testing

The unit tests for the action_manager are located in the catkin_home/src/main_engine/test folder. Some basic tests are performed related to the operations of creating and removing actions from the actions queue.

How to run

  1. Open two terminals in the root folder.

  2. On the first terminal, navigate to the rasa folder and source the python environment for the rasa framework in one of them: cd rasa/ && source venv/bin/activate

  3. Run the rasa server, a message should appear confirming that the server started correctly: ./runrasa.bash

  4. On the second terminal, go into the catkin workspace: cd catkin_home/

  5. Source the ros environment in the other terminal: source devel/setup. bash

  6. Launch the ros node from action_selectors/parser.py and main_engine/src/main_engine/action_manager.py: roslaunch main_engine engine_and_parser_launch.launch

  7. ????

  8. Profit!

References/Support links

RASA actionlib