Shouldn't smach transition even if the action process has died?
Hello,
I am using a smach concurrent state machine and I want it to transition, even if one of the child states has died. It seems like it sits there waiting for the pre-emption to return, when it never will, since the process has died. This leads to undesirable behavior where the state machine will not transition to other states when command messages are sent.
My concurrent state is composed of the following states:
- A simple action state that executes a long running behavior, implemented as a ROS nodelet.
- A monitor state that subscribes to a ROS topic, and transitions when that topic is received.
This all works fine if the nodelet is running as expected. I can publish a topic which the monitor state listens for, the monitor state becomes invalid, and terminates, causing the outcome of the concurrent state to transition to a different state.
The problem comes when the simple action state has died (due to software bugs causing a crash.) Of course, I am fixing these bugs to prevent future crashes of the nodelet process. I am also now setting the problem nodelet to respawn in the launch file. However, for robustness, I would like for the state machine to still transition, even if this process has died.
Is this behavior by design or is there a way to force the concurrence behavior to transition, even if one of the children does not respond to the pre-emption request? In my outcome map, I am using the following, which I thought would cause it to terminate from the monitor state alone, but I think it is waiting for a response from the crashed nodelet.
child_termination_cb=(lambda so: True)
Thanks in advance!
Edit: I am adding my subclassed code for SimpleActionState: Edit2: The code is working now and properly aborts the state:
import roslib
import rospy
import smach
import smach_ros
from smach import State, StateMachine, CBState
from smach_ros import SimpleActionState, IntrospectionServer
from std_msgs.msg import Empty
import threading
import traceback
import copy
from actionlib.simple_action_client import SimpleActionClient, GoalStatus
import smach
from smach.state import *
__all__ = ['WatchdogActionState']
class WatchdogActionState(SimpleActionState):
"""Watchdog Simple action client state.
Subclasses the Smach SimpleActionState to provide watchdog capability on the actionserver process execution.
"""
"""Constructor for SimpleActionState action client wrapper."""
# Overridden constructor:
def __init__(self,
# Action info
action_name,
action_spec,
# Feedback (heartbeat) timeout = how long to wait for a process that has died
# before aborting this state.
feedback_wait_timeout = rospy.Duration(3.0),
# Default goal
goal = None,
goal_key = None,
goal_slots = [],
goal_cb = None,
goal_cb_args = [],
goal_cb_kwargs = {},
# Result modes
result_key = None,
result_slots = [],
result_cb = None,
result_cb_args = [],
result_cb_kwargs = {},
# Keys
input_keys = [],
output_keys = [],
outcomes = ['succeeded','aborted','preempted'],
# Timeouts
exec_timeout = None,
preempt_timeout = rospy.Duration(1.0),
server_wait_timeout = rospy.Duration(1.0)
):
# Initialize base class
rospy.loginfo("init watchdog_action_state for action_name [%s], action_spec [%s]", action_name, action_spec)
SimpleActionState.__init__(self,
action_name,
action_spec,
goal,
goal_key,
goal_slots,
goal_cb,
goal_cb_args,
goal_cb_kwargs,
result_key,
result_slots,
result_cb,
result_cb_args,
result_cb_kwargs,
input_keys,
output_keys,
outcomes,
exec_timeout,
preempt_timeout,
server_wait_timeout)
# The feedback (hearbeat) timeout
self._feedback_wait_timeout = feedback_wait_timeout
rospy.loginfo("server_wait_timeout [%f]", self._feedback_wait_timeout.to_sec())
self._feedback_time = rospy.Time ...
I found a related issue, but it doesn't say how to address the problem with smach: simpleactionstate-behaviour-if-action-server-crashes
I have it working now. I pasted the correct code now, which subclasses SimpleActionState and will abort the state in a separate heartbeat thread if it hasn't received feedback in 3 seconds. If you have any feedback that would be great, but I am marking this as answered. Thanks again.