MoveIt Pro Behavior
Core Behaviors for MoveIt Pro
Loading...
Searching...
No Matches
moveit_studio::behaviors::ComputeVelocityToAlignWithTarget Class Reference

calculates a control velocity that is a sum of the target velocity and a catchup velocity. The target motion state can be offset from the incoming motion state message. The returned control velocity is designed to be sent to the velocity_force_controller. More...

#include <compute_velocity_to_align_with_target.hpp>

Inheritance diagram for moveit_studio::behaviors::ComputeVelocityToAlignWithTarget:
Collaboration diagram for moveit_studio::behaviors::ComputeVelocityToAlignWithTarget:

Public Member Functions

 ComputeVelocityToAlignWithTarget (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< moveit_studio::behaviors::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 ()
 
static BT::KeyValueVector metadata ()
 

Additional Inherited Members

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

Detailed Description

calculates a control velocity that is a sum of the target velocity and a catchup velocity. The target motion state can be offset from the incoming motion state message. The returned control velocity is designed to be sent to the velocity_force_controller.

Data Port Name Port Type Object Type
target_motion_state input nav_msgs::msg::Odometry
target_pose_offset input geometry_msgs::msg::PoseStamped
end_effector_frame input std::string
proportional_gain_linear input double
proportional_gain_angular input double
pose_error output geometry_msgs::msg::PoseStamped
control_velocity output geometry_msgs::msg::TwistStamped

Constructor & Destructor Documentation

◆ ComputeVelocityToAlignWithTarget()

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

Member Function Documentation

◆ metadata()

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

◆ providedPorts()

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

◆ tick()

BT::NodeStatus moveit_studio::behaviors::ComputeVelocityToAlignWithTarget::tick ( )
override

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