![]() |
MoveIt Pro API
Core Behaviors for MoveIt Pro
|
A Behavior to forward JointJog commands to a Joint Velocity Controller. More...
#include <joint_jog.hpp>
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) |
![]() | |
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 | |
![]() | |
std::shared_ptr< BehaviorContext > | shared_resources_ |
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 |
moveit_studio::behaviors::JointJog::JointJog | ( | const std::string & | name, |
const BT::NodeConfiguration & | config, | ||
const std::shared_ptr< moveit_studio::behaviors::BehaviorContext > & | shared_resources | ||
) |
|
inline |
|
inline |
|
static |
|
override |
|
override |
|
override |
|
static |
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 | ||
) |
|
staticconstexpr |
|
staticconstexpr |
|
staticconstexpr |
|
staticconstexpr |
|
staticconstexpr |