MoveIt Pro Behavior
Core Behaviors for MoveIt Pro
moveit_studio::behaviors::AddToVector< InputT > Class Template Reference

Pushes an object into a vector and sets the updated vector to the blackboard. More...

#include <add_to_vector.hpp>

Inheritance diagram for moveit_studio::behaviors::AddToVector< InputT >:
Collaboration diagram for moveit_studio::behaviors::AddToVector< InputT >:

Public Types

using VectorT = std::vector< InputT >
 

Public Member Functions

 AddToVector (const std::string &name, const BT::NodeConfiguration &config)
 
BT::KeyValueVector metadata ()
 
BT::PortsList providedPorts ()
 

Static Public Member Functions

static BT::PortsList providedPorts ()
 
static BT::KeyValueVector metadata ()
 

Static Public Attributes

static constexpr auto kPortIDInput = "input"
 
static constexpr auto kPortIDVector = "vector"
 

Detailed Description

template<typename InputT>
class moveit_studio::behaviors::AddToVector< InputT >

Pushes an object into a vector and sets the updated vector to the blackboard.

Template Parameters
InputTThe type of the input object. Also determines the type of the vector.

If the vector does not exist, calling this behavior will create a new sequence with the given input as first element.

Data Port Name Port Type Object Type
input input T
vector bidirectional std::vector<T>

Member Typedef Documentation

◆ VectorT

template<typename InputT >
using moveit_studio::behaviors::AddToVector< InputT >::VectorT = std::vector<InputT>

Constructor & Destructor Documentation

◆ AddToVector()

template<typename InputT >
moveit_studio::behaviors::AddToVector< InputT >::AddToVector ( const std::string &  name,
const BT::NodeConfiguration &  config 
)

Member Function Documentation

◆ metadata() [1/2]

BT::KeyValueVector moveit_studio::behaviors::AddToVector< geometry_msgs::msg::PoseStamped >::metadata ( )

◆ metadata() [2/2]

template<typename InputT >
static BT::KeyValueVector moveit_studio::behaviors::AddToVector< InputT >::metadata ( )
static

◆ providedPorts() [1/2]

BT::PortsList moveit_studio::behaviors::AddToVector< geometry_msgs::msg::PoseStamped >::providedPorts ( )

◆ providedPorts() [2/2]

template<typename InputT >
static BT::PortsList moveit_studio::behaviors::AddToVector< InputT >::providedPorts ( )
static

Member Data Documentation

◆ kPortIDInput

template<typename InputT >
constexpr auto moveit_studio::behaviors::AddToVector< InputT >::kPortIDInput = "input"
staticconstexpr

◆ kPortIDVector

template<typename InputT >
constexpr auto moveit_studio::behaviors::AddToVector< InputT >::kPortIDVector = "vector"
staticconstexpr

The documentation for this class was generated from the following files: