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

Given a joint-space goal, plan a joint-space trajectory to reach the goal. More...

#include <plan_to_joint_goal.hpp>

Inheritance diagram for moveit_studio::behaviors::PlanToJointGoal:
Collaboration diagram for moveit_studio::behaviors::PlanToJointGoal:

Public Member Functions

 PlanToJointGoal (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources)
 Constructor for PlanToJointGoal behavior. More...
 
 PlanToJointGoal (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< moveit_studio::behaviors::BehaviorContext > &shared_resources, std::unique_ptr< ClientInterfaceBase< GetPlanningScene >> client_interface)
 Constructor for PlanToJointGoal 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< std::chrono::duration< double >, std::string > getResponseTimeout ()
 Optional user-provided function to set the timeout used when waiting for the service response. More...
 
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

Given a joint-space goal, plan a joint-space trajectory to reach the goal.

Data Port Name Port Type Object Type
goal Input moveit_studio_agent_msgs::msg::JointState
planning_group_name Input std::string
velocity_scale_factor Input double
acceleration_scale_factor Input double
trajectory_sampling_rate Input int
link_padding Input double
keep_orientation Input bool
keep_orientation_tolerance Input double
joint_trajectory_msg Output trajectory_msgs::msg::JointTrajectory

Constructor & Destructor Documentation

◆ PlanToJointGoal() [1/2]

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

Constructor for PlanToJointGoal behavior.

◆ PlanToJointGoal() [2/2]

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

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

Member Function Documentation

◆ metadata()

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

◆ providedPorts()

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

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