PositionCondition Node. More...
#include <position_condition.h>
Public Member Functions | |
void | init (const std::string &obj_name, tf2::Vector3 &start_pos, moveit::planning_interface::PlanningSceneInterface *psi) |
Initialize Node. More... | |
PositionCondition (const std::string &name, const BT::NodeConfiguration &config) | |
PositionCondition constructor. More... | |
Static Public Member Functions | |
static BT::PortsList | providedPorts () |
Required port inferface. More... | |
Protected Member Functions | |
virtual BT::NodeStatus | tick () override |
tick function More... | |
Protected Attributes | |
std::string | obj_name_ |
Object name. More... | |
moveit::planning_interface::PlanningSceneInterface * | psi_ |
PSI. More... | |
tf2::Vector3 | start_pos_ |
Start position. More... | |
PositionCondition Node.
Implements a pre-condition, in which Objects require a specific position to be processed.
Definition at line 21 of file position_condition.h.
PositionCondition::PositionCondition | ( | const std::string & | name, |
const BT::NodeConfiguration & | config | ||
) |
PositionCondition constructor.
name | Name displayed in Groot |
config | Node configuration |
Definition at line 3 of file position_condition.cpp.
void PositionCondition::init | ( | const std::string & | obj_name, |
tf2::Vector3 & | start_pos, | ||
moveit::planning_interface::PlanningSceneInterface * | psi | ||
) |
Initialize Node.
obj_name | Name of Object |
start_pos | Position which is to check |
psi | Planning scene interface reference |
Definition at line 6 of file position_condition.cpp.
|
inlinestatic |
Required port inferface.
Definition at line 40 of file position_condition.h.
|
overrideprotectedvirtual |
tick function
Actual object position is retrived by name and checked againt the start position of the execution
obj_name | Name of Object |
start_pos | Position which is to check |
psi | Planning scene interface reference |
Definition at line 12 of file position_condition.cpp.
|
protected |
Object name.
Definition at line 52 of file position_condition.h.
|
protected |
PSI.
Definition at line 53 of file position_condition.h.
|
protected |
Start position.
Definition at line 54 of file position_condition.h.