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

Checks if a joint trajectory is valid, given a PlanningScene. More...

#include <validate_trajectory.hpp>

Inheritance diagram for moveit_studio::behaviors::ValidateTrajectory:
Collaboration diagram for moveit_studio::behaviors::ValidateTrajectory:

Public Member Functions

 ValidateTrajectory (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources)
 
- Public Member Functions inherited from moveit_studio::behaviors::AsyncBehaviorBase
 AsyncBehaviorBase (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources)
 
virtual ~AsyncBehaviorBase ()=default
 
BT::NodeStatus onStart () override
 Required implementation of BT::StatefulActionNode::onStart(). More...
 
BT::NodeStatus onRunning () override
 Required implementation of BT::StatefulActionNode::onRunning(). More...
 
void onHalted () override
 Required implementation of BT::StatefulActionNode::onHalted(). More...
 
void resetStatus ()
 Resets the internal status of this node. More...
 
- 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 Member Functions inherited from moveit_studio::behaviors::AsyncBehaviorBase
virtual tl::expected< void, std::string > doHalt ()
 Optionally implement additional work needed to cleanly interrupt the async process. More...
 
void notifyCanHalt ()
 Called when runAsync() finishes to notify onHalted() that the async process has finished. More...
 
- Protected Attributes inherited from moveit_studio::behaviors::SharedResourcesNode< BT::StatefulActionNode >
std::shared_ptr< BehaviorContextshared_resources_
 

Detailed Description

Checks if a joint trajectory is valid, given a PlanningScene.

This behavior just checks that the joint trajectory is collision-free at a given density (joint_space_step and cartesian_space_step).

The planning scene is taken as input (instead of querying the current planning scene) to enable the user to set arbitrary planning scenes. Combine with the GetCurrentPlanningScene behavior to use the current planning scene.

The given trajectory must contain exclusively the planning group joints, otherwise an error will be returned.

The debug_solution port will contain an MTC Solution message with the portion of the trajectory that passed validation. This can be the entire trajectory if all the setpoints passed validation.

Data Port Name Port Type Object Type
planning_scene_msg Input moveit_msgs::msg::PlanningScene
planning_group_name Input std::string
joint_trajectory_msg Input trajectory_msgs::msg::JointTrajectory
joint_space_step Input double
cartesian_space_step Input double
debug_solution Output moveit_task_constructor_msgs::msg::Solution

Constructor & Destructor Documentation

◆ ValidateTrajectory()

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

Member Function Documentation

◆ metadata()

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

◆ providedPorts()

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

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