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

Move the tip at a velocity in closed loop towards a Cartesian target_pose, using Servo. More...

#include <servo_towards_pose.hpp>

Inheritance diagram for moveit_studio::behaviors::ServoTowardsPose:
Collaboration diagram for moveit_studio::behaviors::ServoTowardsPose:

Public Member Functions

 ServoTowardsPose (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources)
 
BT::NodeStatus onStart () override
 
BT::NodeStatus onRunning () override
 
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

Move the tip at a velocity in closed loop towards a Cartesian target_pose, using Servo.

This Behavior is intended to be used in a Parallel node. With every tick, the error between the current tip pose (for planning_group_name) and the given target_pose is computed. That error is also the direction along which the tip has to move to decrease the error. Therefore, with every tick, this Behavior will send a twist to Servo, to move along the direction that points towards the target. The Cartesian velocity sent to Servo is proportional (with translational_gain and rotational_gain) to the distance to the target, but capped at the given max_translational_vel and max_rotational_vel translational and rotational velocities. Twist messages are published to Servo at the given publish_rate. The Behavior will run indefinitely until cancelled or until the distance to the target falls below the given exit_threshold_translation and exit_threshold_rotation in the 3D translational and rotational axes, for at least the given exit_threshold_time amount of seconds.

Data Port Name Port Type Object Type
planning_group_name Input std::string
target_pose Input geometry_msgs::PoseStamped
translational_gain Input double
rotational_gain Input double
max_translational_vel Input double
max_rotational_vel Input double
exit_threshold_translation Input double
exit_threshold_rotation Input double
exit_threshold_time Input double
publish_rate Input int

Constructor & Destructor Documentation

◆ ServoTowardsPose()

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

Member Function Documentation

◆ metadata()

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

◆ onHalted()

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

◆ onRunning()

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

◆ onStart()

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

◆ providedPorts()

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

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