Public Member Functions | |
def | __init__ (self, name, action_type, goal_formatter=format, result_formatter=format, default_result=None, default_result_delay=0) |
def | __repr__ (self) |
def | connected (self) |
def | start (self) |
def | stop (self) |
Public Member Functions inherited from scenario_test_tools.scriptable_base.ScriptableBase | |
def | __init__ (self, name, goal_formatter=format, reply_formatter=format, default_reply=None, default_reply_delay=0) |
def | add_pre_reply_callback (self, callback) |
def | await_goal (self, timeout=None, marker=None) |
def | clear_goals (self) |
def | current_goal (self) |
def | custom_reply (self) |
def | default_reply (self) |
def | default_reply (self, result) |
def | default_reply_delay (self) |
def | default_reply_delay (self, delay) |
def | direct_reply (self, result, reply_delay=None, marker=None) |
def | match_in_received_goals (self, match_against, key=lambda x:x) |
def | name (self) |
def | received_goals (self) |
def | remember_goals (self) |
def | reply (self, result, timeout=None, reply_delay=None, marker=None) |
def | reply_conditionally (self, condition, true_result, false_result, timeout=None, reply_delay=None, marker=None) |
def | stop (self) |
Public Attributes | |
preemption | |
Public Attributes inherited from scenario_test_tools.scriptable_base.ScriptableBase | |
default_reply | |
goal_formatter | |
result_formatter | |
Static Public Attributes | |
string | ABORT_GOAL = "ABORT_GOAL" |
string | IGNORE_GOAL = "IGNORE_GOAL" |
string | SUCCEED_GOAL = "SUCCEED_GOAL" |
Private Member Functions | |
def | _execute_cb (self) |
def | _preempt_cb (self) |
def | _send_result (self, result_tuple) |
Private Attributes | |
_as | |
_current_goal | |
_next_reply | |
ScriptableActionServer allows its users to determine the ActionResult to an ActionGoal. The result-type for e.g. FooAction should be FooResult, not FooActionResult! Goals can be aborted by setting `ABORT_GOAL` as the result. Goals can be ignored by setting `IGNORE_GOAL` as the result. This makes the action client never get a result Note that Actionlib uses the term 'result' for its, well, results, whereas ROS services use 'reply'. The base class `ScriptableBase` uses the 'reply' terminology. `ScriptableActionServer` should be consistent with the action terminology, so it's constructor does some translation between terms and passes 'default_reply=default_result' to the constructor of `ScriptableBase`.
Definition at line 24 of file scriptable_action_server.py.
def scenario_test_tools.scriptable_action_server.ScriptableActionServer.__init__ | ( | self, | |
name, | |||
action_type, | |||
goal_formatter = format , |
|||
result_formatter = format , |
|||
default_result = None , |
|||
default_result_delay = 0 |
|||
) |
Set up a ScriptableActionServer based on the name and the type of Action it should implement :param action_type: action type (e.g. MoveBaseAction)
Definition at line 45 of file scriptable_action_server.py.
def scenario_test_tools.scriptable_action_server.ScriptableActionServer.__repr__ | ( | self | ) |
Definition at line 61 of file scriptable_action_server.py.
|
private |
Called when the underlying action server receives a goal. If the default_result is None, it will wait for a custom result to be set via reply* otherwise return the default_result after the given default_result_delay In the reply-case,it then notifies self.reply* (which should be called by a test script outside this class), after which self.reply* determines the result to the goal. Then it notifies _execute_cb that the result has been determined so that _execute_cb can send it
Definition at line 78 of file scriptable_action_server.py.
|
private |
Handle action preemption by the action client
Definition at line 150 of file scriptable_action_server.py.
|
private |
Send the result and deal with ignored and aborted goals :param result: a Result associated with the Action-type of this Server
Definition at line 115 of file scriptable_action_server.py.
def scenario_test_tools.scriptable_action_server.ScriptableActionServer.connected | ( | self | ) |
Definition at line 65 of file scriptable_action_server.py.
def scenario_test_tools.scriptable_action_server.ScriptableActionServer.start | ( | self | ) |
Start the action server and thus listen to goals
Definition at line 68 of file scriptable_action_server.py.
def scenario_test_tools.scriptable_action_server.ScriptableActionServer.stop | ( | self | ) |
Definition at line 74 of file scriptable_action_server.py.
|
private |
Definition at line 57 of file scriptable_action_server.py.
|
private |
Definition at line 89 of file scriptable_action_server.py.
|
private |
Definition at line 111 of file scriptable_action_server.py.
|
static |
Definition at line 43 of file scriptable_action_server.py.
|
static |
Definition at line 42 of file scriptable_action_server.py.
scenario_test_tools.scriptable_action_server.ScriptableActionServer.preemption |
Definition at line 155 of file scriptable_action_server.py.
|
static |
Definition at line 41 of file scriptable_action_server.py.