|
| ValidateTrajectory (const std::string &name, const BT::NodeConfiguration &config, const std::shared_ptr< BehaviorContext > &shared_resources) |
|
| 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...
|
|
| 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...
|
|
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 |