This page provides info for the srs_decision_making package included in the srs repository.

Structure

SRS decision making is the centre of the SRS control structure. It contains the following components:

Action Server

At the moment, action server takes high level actions: Move, Search, Get, Stop 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

High-level state machines

Generic states

A generic state template

ROS API

Exception Parsing Clearsilver: ParseError: [<string>:10] Unable to parse line string action

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_v1 (last edited 2011-11-18 21:30:03 by renxi)