Use the /get_planning_scene service from move_group to save the robot's current state.
More...
#include <save_current_state.hpp>
|
| 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 |
|
| 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...
|
|
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 |
◆ SaveCurrentState()
moveit_studio::behaviors::SaveCurrentState::SaveCurrentState |
( |
const std::string & |
name, |
|
|
const BT::NodeConfiguration & |
config, |
|
|
const std::shared_ptr< BehaviorContext > & |
shared_resources |
|
) |
| |
◆ 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: