Only released in EOL distros:  

Structure

SRS decision making is the centre of the SRS control structure. In order to optimise the decision making process, SRS actions are divided into three layers:

  1. Primitive action level: They are basic robot actions developed by other SRS component or imported from care-o-bot. The actions in this level are considered as the generic states in the SRS decision making.
  2. Decision level: They are the action schemas which fulfil certain skills. The actions in this level are considered as the state machines in the SRS decision making.
  3. Task level: They are the basis of SRS high level commands which can be issued by UI for controlling the robot behaviours. SRS application scenarios are constructed by the commands on this level.

In the decision making module, Level 1 and level 2 are connected by a collection of SRS high level state machines within SRS action server. The idea is to connect inputs, outputs and robot configurations of primitive actions together automatically as if the cerebellum of the human brain. Level 2 and level 3 are connected by SRS knowledge service. dm_structure.png

Primitive actions and generic state

Primitive actions are atomic element in SRS decision making. A list of generic state and their corresponding inputs and outputs are listed in the following table

Name of the generic state

Corresponding SRS/COB components

Inputs

Outputs

Outcomes

approach_pose()

COB navigation

Target 2D Pose

'succeeded', 'failed'

approach_pose_without_retry()

COB navigation

Target 2D Pose

'succeeded', 'failed'

grasp()

SRS assisted grasp+COB manipulation

Target object ID + Optional: Grasp configuration categorisation (top, side etc.)

Target object pose before grasp

'succeeded' 'retry' 'no_more_retry' 'failed'

detect_object()

SRS assisted detection

List of object IDs Optional: Bounding _box

List of identified pose and corresponding ID

'succeeded' 'retry' 'no_more_retry' 'failed'

Environment_update()

SRS environment perception

List of object IDs Optional: Bounding _region

List of identified pose and corresponding ID

'succeeded' 'retryno_more_retry' 'failed'

put_object_on_tray()

COB manipulation

'succeeded', 'failed'

Placing_object()

COB manipulation

Target 3D coordinate

'succeeded', 'failed'

Open_door()

Door_ID

'succeeded' 'retry' 'no_more_retry' 'failed'

A template of the generic state is listed below:

class name_of_the_state(smach.State):

    def __init__(self):
        smach.State.__init__(
            self,
            outcomes=['outcome1', 'outcome2', 'etc'], 
            input_keys=['input1', "input2","etc"],    # a key can be both input_key and output_key
            output_keys=['output1', "output2","etc"]  # input_key and output_key can be empty                        
            )
        #initialise internal memory
        #self.something=""


    def execute(self, userdata):
        #initialise all output keys, other wise higher state machine may raise errors
        userdata.output1=""
        userdata.output2=""
        userdata.etc=""
        #initialise all output keys completed
        
        #checking robot configuration before action (optional)
        #
        #checking robot configuration before action finished
        
        #do your programme
        #you can refer the input_key or output_key by userdata.name_of_the_key
        
              
        #checking robot configuration  after action (optional)
        #
        #checking robot configuration  after action completed (optional)
        
        #return one of the outcome defined above
        return 'outcome1' 

Required message formation: To be added

High level state machines

In SRS implementation, action schemas are realised by ROS smash as robot control state machines and integrated with hardware platform with the SRS generic states defined above.

SRS high level state machines are listed in the following table:

Actions

Required inputs

Outputs

Outcomes

SM_Navigation

Target 2d pose Operation status(no object, or with object in SDH, or with object on tray)

'Completed' 'Not completed' 'Failed'

SM_Detection(for detecting only)

List of Target ID, Optional: Bounding _region_3D

List of identified pose and corresponding ID

'Completed' 'Not completed' 'Failed'

SM_Environment_update

List of Target ID, Optional: Bounding _region_2D

List of identified pose and corresponding ID

'Completed' 'Not completed' 'Failed'

SM_Simple_Grasp (Detection for grasping + grasping after object detected)

Target object ID

Last pose of the object before grasp

'Completed' 'Not completed' 'Failed'

SM_Grasp (sm_simple_grasp + open door)

Target object ID. Door ID

Last pose of the object before grasp

'Completed' 'Not completed' 'Failed'

SM_After_Grasp (Placing object on tray etc.)

Object configuration (on tray or in SDH)

'Completed' 'Not completed' 'Failed'

SM_Placing (Placing object at delivery location)

Target object ID (The id of the target workspace)

'Completed' 'Not completed' 'Failed'

SRS high level commands

SRS high level commands are normally issued by users. As part of user interaction process, it needs to be a close loop e.g. starts from the idle state and also ends at the idle state.

High level commands (and there corresponding parameters) required by SRS fetch and carry scenario are list in the following table:

action

parameters

priority

move

Target

Example: "move ChargingStation0"

search

Target object name + Search_area (optional)

Example: "search Milkbox Table0 Table1"

get

Target object name + Search_area (optional)

Example: "get Milkbox Table0 Table1"

fetch

Target object name + Order_position + Search_area (optional)

Example: "fetch Book0 order Bookshelf0 Table0"

deliver

Target object name + Target deliver position + Search_area(optional)

Example: "deliver Milkbox KitchenCounter0 Table0 Table1"

stop

pause

resume

Note1: Compared to other high level commands, stop command does not start from idle. The actual behaviour is depended on the place where the command is issued. E.g., the stop command issued before object has been grasped won’t be same as it is issued after the object has been grasped. SRS decision making will provide optimised policy accordingly by analysing the circumstance and context in real time.

Note2: Commands above can be reorganised in hierarchy for more complicated task such as setting table. They will be expanded in the further SRS development.

Note3: The commands "stop", "pause" and "resume" do not take any parameters. Parameters are separated by a blank character. The optional parameter "Search_area" is always at the end and may consist of several places or none at all.

Note4: "Book0" and "Milkbox" are object IDs. "Table0", "Table1", "KitchenCounter0" and "Bookshelf0" are workspaces. "order" and "ChargingStation0" are predefined poses.

high_level_commands.png

Action Server

At the moment, action server takes high level actions: Move, Search, Get, Stop, Pause, Resume. This list will be further expanded with the project development.

SRS Action server follows ROS actionlib formation. For more details check the ROS action lib document

Based on the ros actionlib, SRS action server publish the following topics:

/srs_decision_making_actions/cancel
/srs_decision_making_actions/feedback
/srs_decision_making_actions/goal
/srs_decision_making_actions/result
/srs_decision_making_actions/status

ROS API

srs_decision_making_actions/goal

string action
string[] parameters
uint32 priority
string client_id
string client_type

high level action name, parameters, priority, client id and client type.

srs_decision_making_actions/result

uint32 return_value
#3 succeeded, 4 failed, 2 preemptied

high level action name, parameter and priority

srs_decision_making_actions/feedback

string current_state
bool solution_required
uint32 exceptional_case_id
#  1 intervention for base pose needed
#  2 intervention for key region needed
#  3 intervention for grasp catergorisation needed
#  4 intervention for action sequences needed

What is the current action, user intervention is required or not, what kind of intervention is needed

Usage/Examples

Writing a simple action client

import roslib; roslib.load_manifest('srs_decision_making')
import rospy

# Brings in the SimpleActionClient
import actionlib

# Brings in the messages used by the SRS DM action, including the
# goal message and the result message.
import srs_decision_making.msg as xmsg

def DM_client():
    # Creates the SimpleActionClient, passing the type of the action
    # constructor.
    client = actionlib.SimpleActionClient('srs_decision_making_actions', xmsg.ExecutionAction)

    # Waits until the action server has started up and started
    # listening for goals.
    client.wait_for_server()

    # Creates a goal to send to the action server.
    _goal=xmsg.ExecutionGoal()
    _goal.action="get"
    _goal.parameter="milk"
    _goal.priority=0
    # Sends the goal to the action server.
    client.send_goal(_goal)

    # Waits for the server to finish performing the action.
    client.wait_for_result()

    # Prints out the result of executing the action
    return client.get_result()

if __name__ == '__main__':
    try:
        # Initializes a rospy node so that the SimpleActionClient can
        # publish and subscribe over ROS.
        rospy.init_node('dm_client')
        result = DM_client()
        rospy.loginfo('result %s',result)
        # print ("Result:" result)
    except rospy.ROSInterruptException:
        print "program interrupted before completion"

Writing an action client for sending action sequence

    client = actionlib.SimpleActionClient('srs_decision_making_actions', xmsg.ExecutionAction)
    # Waits until the action server has started up and started
    # listening for goals.
    client.wait_for_server()
    # creates action sequence for the action server
    sequence=[]
    # Creates a goal to send to the action server.
    _goal=xmsg.ExecutionGoal()
    _goal.action="move"
    _goal.parameter="kitchen"
    _goal.priority=0
    sequence.append(_goal)
    _goal.action="search"
    _goal.parameter="milk"
    _goal.priority=0
    sequence.append(_goal)
    # Sends the goal to the action server.
    for item in sequence:
        client.send_goal(item)
        # Waits for the server to finish performing the action.
        client.wait_for_result()
        #check result
        if client.get_result()!=3:
            return client.get_result()
    # Prints out the result of executing the action
    return client.get_result()

Wiki: srs_decision_making (last edited 2012-06-13 08:34:07 by MarKre)