|  | MoveIt Pro API
    Core Behaviors for MoveIt Pro | 
This behavior creates a stationary trajectory of specified duration at the provided JointState ROS message.  
 More...
#include <create_stationary_trajectory.hpp>


| Public Member Functions | |
| CreateStationaryTrajectory (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) | |
| BT::NodeStatus | tick () override | 
|  Public Member Functions inherited from moveit_studio::behaviors::SharedResourcesNode< BT::SyncActionNode > | |
| 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. | |
| Static Public Member Functions | |
| static BT::PortsList | providedPorts () | 
| Required implementation of static providedPorts function. | |
| static BT::KeyValueVector | metadata () | 
| Additional Inherited Members | |
|  Protected Attributes inherited from moveit_studio::behaviors::SharedResourcesNode< BT::SyncActionNode > | |
| std::shared_ptr< BehaviorContext > | shared_resources_ | 
This behavior creates a stationary trajectory of specified duration at the provided JointState ROS message. 
| Data Port Name | Port Type | Object Type | 
|---|---|---|
| joint_state | Input | sensor_msgs::msg::JointState | 
| trajectory_duration | Input | double | 
| joint_trajectory_msg | Output | trajectory_msgs::msg::JointTrajectory | 
| moveit_studio::behaviors::CreateStationaryTrajectory::CreateStationaryTrajectory | ( | const std::string & | name, | 
| const BT::NodeConfiguration & | config, | ||
| const std::shared_ptr< BehaviorContext > & | shared_resources | ||
| ) | 
| 
 | static | 
| 
 | static | 
Required implementation of static providedPorts function.
| 
 | override |