Skip to content

Using a ReactiveSequence with asynch condition #875

Closed
@AndyZe

Description

@AndyZe

TLDR: don't use an asynch action for the condition in a ReactiveSequence.

I have a simple ReactiveSequence like this. It's very similar to the example here:

    <!-- Keep running DummyStatefulAction as long as the monitors are good -->
    <ReactiveSequence>
        <CheckJointVelocityMonitor1/>  <!-- Inherits from BT::RosServiceNode -->
        <DummyStatefulAction/>            <!-- A long-running asynch action -->
    </ReactiveSequence>

The prints when this BT is executing are:

CheckJointVelocityMonitor1 returning SUCCESS  // This BT node always returns success
Starting DummyStatefulAction                                // This is expected, it comes from .onStart(), which returns BT::NodeStatus::RUNNING
DummyStatefulAction halted!                                  // I don't understand where the halt comes from
CheckJointVelocityMonitor1 returning SUCCESS
Starting DummyStatefulAction
DummyStatefulAction halted!
CheckJointVelocityMonitor1 returning SUCCESS
Starting DummyStatefulAction
DummyStatefulAction halted!
CheckJointVelocityMonitor1 returning SUCCESS
Starting DummyStatefulAction
DummyStatefulAction halted!
  ... loop continues

CheckJointVelocityMonitor1 always returns SUCCESS. I've verified with print statements. DummyStatefulAction appears to be ticked once and returns RUNNING, then it gets halted. I don't understand why it gets halted. (Edit: it gets halted because it returns RUNNING.)

Here's the declaration for DummyStatefulAction, which inherits from BT::StatefulActionNode.

class DummyStatefulAction : public BT::StatefulActionNode
{
public:
  DummyStatefulAction(const std::string& name, const BT::NodeConfiguration& config) : StatefulActionNode(name, config)
  {
  }

  static BT::PortsList providedPorts();

  BT::NodeStatus onStart() override;

  BT::NodeStatus onRunning() override;

  void onHalted() override;
};

Here's the definition for DummyStatefulAction. It only returns RUNNING, never SUCCESS or FAILURE.

BT::NodeStatus DummyStatefulAction::onStart()
{
  std::cerr << "Starting DummyStatefulAction" << std::endl;
  return BT::NodeStatus::RUNNING;
}

BT::NodeStatus DummyStatefulAction::onRunning()
{
  std::cerr << "Running DummyStatefulAction" << std::endl;
  return BT::NodeStatus::RUNNING;
}

void DummyStatefulAction::onHalted()
{
  std::cerr << "DummyStatefulAction halted!" << std::endl;
}

Metadata

Metadata

Assignees

No one assigned

    Labels

    No labels
    No labels

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions