Loads the configuration parameters for a given objective. The configuration file name is given as an input port parameters to this behavior. The parameters are loaded once per objective execution. To reload the parameter from the file, just execute the objective again.
More...
#include <load_objective_parameters.hpp>
|
| LoadObjectiveParameters (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) |
| Constructor for LoadObjectiveParameters behavior. More...
|
|
BT::NodeStatus | tick () override |
| Synchronous, blocking function that must return SUCCESS/FAILURE every time this action node is ticked by the behavior tree. More...
|
|
| 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. More...
|
|
|
static BT::PortsList | providedPorts () |
| Custom tree nodes that have input and/or output ports must define them in this static function. More...
|
|
static BT::KeyValueVector | metadata () |
|
Loads the configuration parameters for a given objective. The configuration file name is given as an input port parameters to this behavior. The parameters are loaded once per objective execution. To reload the parameter from the file, just execute the objective again.
Data Port Name | Port Type | Object Type |
config_file_name | input | std::string |
parameters | output | YAML::Node |
◆ LoadObjectiveParameters()
moveit_studio::behaviors::LoadObjectiveParameters::LoadObjectiveParameters |
( |
const std::string & |
name, |
|
|
const BT::NodeConfiguration & |
config, |
|
|
const std::shared_ptr< BehaviorContext > & |
shared_resources |
|
) |
| |
Constructor for LoadObjectiveParameters behavior.
- Parameters
-
name | Name of the node. Must match the name used for this node in the behavior tree definition file (the .xml file). |
config | Node configuration. Only used here because the BehaviorTree.CPP expects constructor signature with name and config first before custom constructor parameters. |
shared_resources | Provides access to common resources such as the node handle and failure logger that are shared between all the behaviors that inherit from moveit_studio::behaviors::SharedResourcesNode. |
◆ metadata()
BT::KeyValueVector moveit_studio::behaviors::LoadObjectiveParameters::metadata |
( |
| ) |
|
|
static |
◆ providedPorts()
BT::PortsList moveit_studio::behaviors::LoadObjectiveParameters::providedPorts |
( |
| ) |
|
|
static |
Custom tree nodes that have input and/or output ports must define them in this static function.
This function must be static. It is a requirement set by the BehaviorTree.CPP library.
- Returns
- List of ports with the names and port info. The return value is for the internal use of the behavior tree.
◆ tick()
BT::NodeStatus moveit_studio::behaviors::LoadObjectiveParameters::tick |
( |
| ) |
|
|
override |
Synchronous, blocking function that must return SUCCESS/FAILURE every time this action node is ticked by the behavior tree.
- Returns
- Status of the node. Must be either SUCCESS/FAILURE (the node is "complete" for now). Cannot be RUNNING since this is a synchronous node.
The documentation for this class was generated from the following files: