MoveIt Pro API
Core Behaviors for MoveIt Pro
Loading...
Searching...
No Matches
moveit_studio::behaviors::JointJog Class Reference

A Behavior to forward JointJog commands to a Joint Velocity Controller. More...

#include <joint_jog.hpp>

Inheritance diagram for moveit_studio::behaviors::JointJog:
Collaboration diagram for moveit_studio::behaviors::JointJog:

Public Member Functions

 JointJog (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< moveit_studio::behaviors::BehaviorContext > &shared_resources)
 
BT::NodeStatus onStart () override
 
BT::NodeStatus onRunning () override
 
void onHalted () override
 
const planning_scene_monitor::PlanningSceneMonitor & getPlanningSceneMonitor () const
 
planning_scene_monitor::PlanningSceneMonitor & getPlanningSceneMonitor ()
 
void setParametersFromJointVelocityController (std::string_view joint_model_group_name, const Eigen::VectorXd &controller_max_joint_acceleration, const Eigen::VectorXd &controller_max_joint_velocity)
 
- 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.
 

Static Public Member Functions

static BT::PortsList providedPorts ()
 
static BT::KeyValueVector metadata ()
 

Static Public Attributes

static constexpr auto kPortIdControllerName = "controller_name"
 
static constexpr auto kPortIdLinkPadding = "link_padding"
 
static constexpr auto kPortIdStopSafetyFactor = "stop_safety_factor"
 
static constexpr auto kPortIdIncludeOctomap = "include_octomap"
 
static constexpr auto kPortIdSkipCollisionChecks = "skip_collision_checks"
 

Additional Inherited Members

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

Detailed Description

A Behavior to forward JointJog commands to a Joint Velocity Controller.

This Behavior will subscribe to messages of type control_msgs/JointJog, and forward them to a Joint Velocity Controller for execution. The behavior acts as a bridge, forwarding commands to the controller only if they are 'safe' to execute, i.e. not predicted to cause a collision in the near future, or hit joint limits.

The planning group to control is retrieved from the Joint Velocity Controller's (JVC) parameter server, since each JVC instance is configured to control a specific planning group.

A link padding can be specified to virtually increase the size of the robot links for collision checking. A stop safety factor can be specified to increase the time horizon for the stop trajectory collision check.

Data Port Name Port Type Object Type
controller_name Input std::string
link_padding Input double
stop_safety_factor Input double
include_octomap Input bool
skip_collision_checks Input bool

Constructor & Destructor Documentation

◆ JointJog()

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

Member Function Documentation

◆ getPlanningSceneMonitor() [1/2]

planning_scene_monitor::PlanningSceneMonitor & moveit_studio::behaviors::JointJog::getPlanningSceneMonitor ( )
inline

◆ getPlanningSceneMonitor() [2/2]

const planning_scene_monitor::PlanningSceneMonitor & moveit_studio::behaviors::JointJog::getPlanningSceneMonitor ( ) const
inline

◆ metadata()

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

◆ onHalted()

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

◆ onRunning()

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

◆ onStart()

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

◆ providedPorts()

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

◆ setParametersFromJointVelocityController()

void moveit_studio::behaviors::JointJog::setParametersFromJointVelocityController ( std::string_view  joint_model_group_name,
const Eigen::VectorXd &  controller_max_joint_acceleration,
const Eigen::VectorXd &  controller_max_joint_velocity 
)

Member Data Documentation

◆ kPortIdControllerName

constexpr auto moveit_studio::behaviors::JointJog::kPortIdControllerName = "controller_name"
staticconstexpr

◆ kPortIdIncludeOctomap

constexpr auto moveit_studio::behaviors::JointJog::kPortIdIncludeOctomap = "include_octomap"
staticconstexpr

◆ kPortIdLinkPadding

constexpr auto moveit_studio::behaviors::JointJog::kPortIdLinkPadding = "link_padding"
staticconstexpr

◆ kPortIdSkipCollisionChecks

constexpr auto moveit_studio::behaviors::JointJog::kPortIdSkipCollisionChecks = "skip_collision_checks"
staticconstexpr

◆ kPortIdStopSafetyFactor

constexpr auto moveit_studio::behaviors::JointJog::kPortIdStopSafetyFactor = "stop_safety_factor"
staticconstexpr

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