00001 #ifndef ACTION_EXECUTOR_ARM_TO_CARRY_H 00002 #define ACTION_EXECUTOR_ARM_TO_CARRY_H 00003 00004 #include "continual_planning_executive/actionExecutorActionlib.hpp" 00005 #include "continual_planning_executive/symbolicState.h" 00006 #include <tidyup_msgs/PostGraspPositionAction.h> 00007 00008 namespace tidyup_actions 00009 { 00010 00011 class ActionExecutorArmToCarry : public ActionExecutorActionlib<tidyup_msgs::PostGraspPositionAction, 00012 tidyup_msgs::PostGraspPositionGoal, tidyup_msgs::PostGraspPositionResult> 00013 { 00014 public: 00022 virtual void initialize(const std::deque<std::string> & arguments); 00023 00024 virtual bool fillGoal(tidyup_msgs::PostGraspPositionGoal & goal, 00025 const DurativeAction & a, const SymbolicState & current); 00026 00027 virtual void updateState(const actionlib::SimpleClientGoalState & actionReturnState, const tidyup_msgs::PostGraspPositionResult & result, 00028 const DurativeAction & a, SymbolicState & current); 00029 00030 private: 00031 std::string _armStatePredicateName; // the arm state predicate name 00032 std::string _armAtCarryConstantName; // the arm at carry position constant name 00033 }; 00034 00035 }; 00036 00037 #endif 00038