Execution node as StatefulActionNode. More...
#include <execution.h>

Public Member Functions | |
| Execution (const std::string &name, const BT::NodeConfiguration &config) | |
| constructor More... | |
| void | init (std::map< std::string, std::pair< moveit_msgs::RobotTrajectory, moveit_msgs::PlanningScene >> *executions_, AbstractRobotDecorator *mr_reference_, moveit_task_constructor_msgs::ExecuteTaskSolutionGoal &ets_) |
| Initialize Node. More... | |
| void | onHalted () override |
| Function called on halt. More... | |
| BT::NodeStatus | onRunning () override |
| Function called while node is in running state. More... | |
| BT::NodeStatus | onStart () override |
| Function called at first execution. More... | |
Static Public Member Functions | |
| static BT::PortsList | providedPorts () |
| Required port interface. More... | |
Private Attributes | |
| moveit_task_constructor_msgs::ExecuteTaskSolutionGoal | ets_ |
| ExecuteTaskSolutionGoal, which is a reference to trajetory and planningscene. More... | |
| std::map< std::string, std::pair< moveit_msgs::RobotTrajectory, moveit_msgs::PlanningScene > > * | executions_ |
| trajetory and planningscene mapped to robot More... | |
| std::vector< moveit_task_constructor_msgs::SubTrajectory >::iterator | it_ |
| next iteration of ExecuteTaskSolutionGoal More... | |
| AbstractRobotDecorator * | mr_reference_ |
| Reference to the robot. More... | |
Execution node as StatefulActionNode.
Execution node that maintains its state (success, failure or execution). It implements robot task execution as a model in which robots can be treated as threads. It represents a container of successive tasks that a robot has to execute and stores a trajectory and a planning scene per task and robot.
Definition at line 23 of file execution.h.
| Execution::Execution | ( | const std::string & | name, |
| const BT::NodeConfiguration & | config | ||
| ) |
constructor
| name | Name displayed in Groot |
| config | Node configuration |
Definition at line 3 of file execution.cpp.
| void Execution::init | ( | std::map< std::string, std::pair< moveit_msgs::RobotTrajectory, moveit_msgs::PlanningScene >> * | executions_, |
| AbstractRobotDecorator * | mr_reference_, | ||
| moveit_task_constructor_msgs::ExecuteTaskSolutionGoal & | ets_ | ||
| ) |
Initialize Node.
| executions_ | |
| mr_reference_ | |
| ets_ |
Definition at line 30 of file execution.cpp.
|
override |
Function called on halt.
Definition at line 28 of file execution.cpp.
|
override |
Function called while node is in running state.
Definition at line 18 of file execution.cpp.
|
override |
Function called at first execution.
Definition at line 6 of file execution.cpp.
|
inlinestatic |
Required port interface.
Definition at line 49 of file execution.h.
|
private |
ExecuteTaskSolutionGoal, which is a reference to trajetory and planningscene.
Definition at line 25 of file execution.h.
|
private |
trajetory and planningscene mapped to robot
Definition at line 27 of file execution.h.
|
private |
next iteration of ExecuteTaskSolutionGoal
Definition at line 28 of file execution.h.
|
private |
Reference to the robot.
Definition at line 26 of file execution.h.