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

Use the /get_planning_scene service from move_group to save the robot's current state. More...

#include <save_current_state.hpp>

Inheritance diagram for moveit_studio::behaviors::SaveCurrentState:
Collaboration diagram for moveit_studio::behaviors::SaveCurrentState:

Public Member Functions

 SaveCurrentState (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources)
 
BT::NodeStatus onStart () override
 Creates an /get_planning_scene service client and checks for the availability of a corresponding service server. More...
 
BT::NodeStatus onRunning () override
 Sends a request to the /get_planning_scene service, and waits for a response to be received. More...
 
void onHalted () override
 
- 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

- Protected Attributes inherited from moveit_studio::behaviors::SharedResourcesNode< BT::StatefulActionNode >
std::shared_ptr< BehaviorContextshared_resources_
 

Detailed Description

Use the /get_planning_scene service from move_group to save the robot's current state.

Data Port Name Port Type Object Type
saved_robot_state Output sensor_msgs::msg::JointState

Constructor & Destructor Documentation

◆ SaveCurrentState()

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

Member Function Documentation

◆ metadata()

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

◆ onHalted()

void moveit_studio::behaviors::SaveCurrentState::onHalted ( )
override

◆ onRunning()

BT::NodeStatus moveit_studio::behaviors::SaveCurrentState::onRunning ( )
override

Sends a request to the /get_planning_scene service, and waits for a response to be received.

method invoked by an action in the RUNNING state.

Returns
Success if the service response is received and the response status is successful. Failure if the service response is not received before the timeout. Failure if the response status is not successful.

◆ onStart()

BT::NodeStatus moveit_studio::behaviors::SaveCurrentState::onStart ( )
override

Creates an /get_planning_scene service client and checks for the availability of a corresponding service server.

Returns
Running if the service server exists, Failure if it does not exist.

◆ providedPorts()

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

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