MoveIt Pro Behavior
Core Behaviors for MoveIt Pro
moveit_studio::behaviors::CreateJointState Class Referencefinal

Create a sensor_msgs::msg::JointState and writes it to the Blackboard. More...

#include <create_joint_state.hpp>

Inheritance diagram for moveit_studio::behaviors::CreateJointState:
Collaboration diagram for moveit_studio::behaviors::CreateJointState:

Public Member Functions

 CreateJointState (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources)
 Constructor for CreateJointState behavior. More...
 
 CreateJointState (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources, std::unique_ptr< ClientInterfaceBase< GetPlanningScene >> client_interface)
 Constructor for CreateJointState behavior that allows for mocking of the rclcpp service client. More...
 
- Public Member Functions inherited from moveit_studio::behaviors::ServiceClientBehaviorBase< GetPlanningScene >
 ServiceClientBehaviorBase (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources)
 Constructs ServiceClientBehaviorBase using the RclcppClientInterface. More...
 
 ServiceClientBehaviorBase (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources, std::unique_ptr< ClientInterfaceBase< GetPlanningScene >> client_interface)
 Constructs ServiceClientBehaviorBase using a user-provided implementation of ClientInterfaceBase. More...
 
virtual ~ServiceClientBehaviorBase ()=default
 
- Public Member Functions inherited from moveit_studio::behaviors::AsyncBehaviorBase
 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(). More...
 
BT::NodeStatus onRunning () override
 Required implementation of BT::StatefulActionNode::onRunning(). More...
 
void onHalted () override
 Required implementation of BT::StatefulActionNode::onHalted(). More...
 
void resetStatus ()
 Resets the internal status of this node. More...
 
- Public Member Functions inherited from moveit_studio::behaviors::SharedResourcesNode< BT::StatefulActionNode >
 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 Public Member Functions

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

Additional Inherited Members

- Static Public Attributes inherited from moveit_studio::behaviors::ServiceClientBehaviorBase< GetPlanningScene >
static constexpr std::chrono::seconds kTimeoutWaitForServiceServer
 
- Protected Member Functions inherited from moveit_studio::behaviors::ServiceClientBehaviorBase< GetPlanningScene >
virtual tl::expected< bool, std::string > processResponse (const typename ServiceT::Response &)
 Optional user-provided function to process the service response after the service has finished. More...
 
- Protected Member Functions inherited from moveit_studio::behaviors::AsyncBehaviorBase
void notifyCanHalt ()
 Called when runAsync() finishes to notify onHalted() that the async process has finished. More...
 
- Protected Attributes inherited from moveit_studio::behaviors::SharedResourcesNode< BT::StatefulActionNode >
std::shared_ptr< BehaviorContextshared_resources_
 

Detailed Description

Create a sensor_msgs::msg::JointState and writes it to the Blackboard.

Data Port Name Port Type Object Type
joint_names input std::vector<std::string>
positions input std::vector<double>
velocities input std::vector<double>
efforts input std::vector<double>
joint_state_msg output sensor_msgs::msg::JointState

This Behavior takes the current JointState of the robot and overwrites the positions, velocities and efforts of those joints indicated in the 'joint_names' input port. 'joint_names' and 'positions' are mandatory, and their sizes have to match. Otherwise an error will be returned. 'velocities' and 'efforts' are optional. If specified, their size needs to match with the size of 'joint_names'.

The current robot JointState is retrieved by a call to the '/get_planning_scene' service, which contains the full robot state.

Constructor & Destructor Documentation

◆ CreateJointState() [1/2]

moveit_studio::behaviors::CreateJointState::CreateJointState ( const std::string &  name,
const BT::NodeConfiguration &  config,
const std::shared_ptr< BehaviorContext > &  shared_resources 
)

Constructor for CreateJointState behavior.

◆ CreateJointState() [2/2]

moveit_studio::behaviors::CreateJointState::CreateJointState ( const std::string &  name,
const BT::NodeConfiguration &  config,
const std::shared_ptr< BehaviorContext > &  shared_resources,
std::unique_ptr< ClientInterfaceBase< GetPlanningScene >>  client_interface 
)

Constructor for CreateJointState behavior that allows for mocking of the rclcpp service client.

Member Function Documentation

◆ metadata()

BT::KeyValueVector moveit_studio::behaviors::CreateJointState::metadata ( )
static

◆ providedPorts()

BT::PortsList moveit_studio::behaviors::CreateJointState::providedPorts ( )
static

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