|
| SwitchController (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) |
|
| SwitchController (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources, std::unique_ptr< ClientInterfaceBase< SwitchControllerSrv > > client_interface) |
|
| ServiceClientBehaviorBase (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) |
| Constructs ServiceClientBehaviorBase using the RclcppClientInterface.
|
|
| ServiceClientBehaviorBase (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources, std::unique_ptr< ClientInterfaceBase< SwitchControllerSrv > > client_interface) |
| Constructs ServiceClientBehaviorBase using a user-provided implementation of ClientInterfaceBase.
|
|
virtual | ~ServiceClientBehaviorBase ()=default |
|
| AsyncBehaviorBase (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) |
|
virtual | ~AsyncBehaviorBase ()=default |
|
BT::NodeStatus | onStart () override |
| Required implementation of BT::StatefulActionNode::onStart().
|
|
BT::NodeStatus | onRunning () override |
| Required implementation of BT::StatefulActionNode::onRunning().
|
|
void | onHalted () override |
| Required implementation of BT::StatefulActionNode::onHalted().
|
|
void | resetStatus () |
| Resets the internal status of this node.
|
|
| SharedResourcesNode (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) |
| Constructor for SharedResourcesNode. Called by BT::BehaviorTreeFactory when creating a new behavior tree containing this node.
|
|
A Behavior to call the ros2_control switch_controllers
service.
This behavior switches controllers in a ros2_control controller manager. Given a list of controllers to activate/deactivate, a service request is dispatched to switch the active ros2_control controllers accordingly. The behavior will wait for the service response and return success or failure based on the response.
Data Port Name | Port Type | Object Type |
activate_controllers | input | std::vector<std::string> |
deactivate_controllers | input | std::vector<std::string> |
strictness | input | int |
activate_asap | input | bool |
timeout | input | std::chrono::duration<double> |
controller_switch_action_name | input | std::string |