GoalManager.h
Go to the documentation of this file.
00001 
00008 #ifndef GOAL_MANAGER_H
00009 #define GOAL_MANAGER_H
00010 
00011 #include <actionlib_msgs/GoalStatus.h>
00012 
00017 class GoalManager
00018 {
00019 public:
00020     GoalManager() : ready(true) {}
00021     GoalManager(const GoalManager& in) : goalStatus(in.getStatus()), ready(in.isReady()) {}
00022     virtual ~GoalManager() {}
00023 
00027     inline const actionlib_msgs::GoalStatus& getStatus() const {return goalStatus;}
00028     inline void setGoalId(const actionlib_msgs::GoalID& goalId) {goalStatus.goal_id = goalId;}
00029     inline void setGoalId(const ros::Time& stamp, const std::string& id)
00030         {goalStatus.goal_id.stamp = stamp; goalStatus.goal_id.id = id;}
00031     inline void setStatus(const actionlib_msgs::GoalStatus::_status_type& status) {goalStatus.status = status;}
00032     inline void setText(const std::string& text) {goalStatus.text = text;}
00033 
00037     inline bool isReady() const {return ready;}
00038     inline void setReadyState(bool ready_in) {ready = ready_in;}
00039     void reset(bool readyState = true)
00040     {
00041         setReadyState(readyState);
00042         goalStatus = actionlib_msgs::GoalStatus();
00043     }
00044 
00045 private:
00046     // message for status updates
00047     actionlib_msgs::GoalStatus goalStatus;
00048     // status bit
00049     bool ready;
00050 };
00051 
00052 #endif


robodyn_controllers
Author(s):
autogenerated on Sat Jun 8 2019 20:20:53