|
MoveIt Pro API
Core Behaviors for MoveIt Pro
|
A Behavior to protect a robot from collisions when using the MoveIt Pro Velocity Force Controller (VFC). More...
#include <pose_jog.hpp>


Public Member Functions | |
| PoseJog (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 () |
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 | kPortIdPlanningGroupNames = "planning_group_names" |
| static constexpr auto | kPortIdControllerNames = "controller_names" |
| static constexpr auto | kPortIdStopSafetyFactor = "stop_safety_factor" |
| static constexpr auto | kPortIdLinkPadding = "link_padding" |
| 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< BehaviorContext > | shared_resources_ |
A Behavior to protect a robot from collisions when using the MoveIt Pro Velocity Force Controller (VFC).
This Behavior will subscribe to messages of type moveit_pro_controllers_msgs/VelocityForceCommand, check that they are valid (e.g. kinematically feasible and non-colliding), and forward them to a Velocity Force Controller (VFC) for execution. Multiple planning groups can be controlled by this Behavior, each with its own VFC.
| Data Port Name | Port Type | Object Type |
|---|---|---|
| planning_group_names | Input | std::vector<std::string> |
| controller_names | Input | std::vector<std::string> |
| stop_safety_factor | Input | double |
| link_padding | Input | double |
| include_octomap | Input | bool |
| skip_collision_checks | Input | bool |
| moveit_studio::behaviors::PoseJog::PoseJog | ( | 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 |
|
staticconstexpr |
|
staticconstexpr |
|
staticconstexpr |
|
staticconstexpr |
|
staticconstexpr |
|
staticconstexpr |