1 #ifndef RAM_PATH_PLANNING_PATH_PLANNING_ALGORITHM_IMP_HPP 2 #define RAM_PATH_PLANNING_PATH_PLANNING_ALGORITHM_IMP_HPP 6 template<
class ActionSpec>
8 const std::string description,
9 const std::string service_name) :
11 description_(description),
12 service_name_(service_name)
16 template<
class ActionSpec>
21 template<
class ActionSpec>
27 if (gh.
getGoalStatus().status != actionlib_msgs::GoalStatus::ACTIVE)
30 action.action_feedback.feedback.progress_value = percentage;
35 template<
class ActionSpec>
41 if (gh.
getGoalStatus().status != actionlib_msgs::GoalStatus::ACTIVE)
44 action.action_feedback.feedback.progress_msg = progress_msg;
50 template<
class ActionSpec>
52 const unsigned percentage,
57 if (gh.
getGoalStatus().status != actionlib_msgs::GoalStatus::ACTIVE)
60 action.action_feedback.feedback.progress_value = percentage;
61 action.action_feedback.feedback.progress_msg = progress_msg;
void publishFeedback(const Feedback &feedback)
bool publishStatusDone(const std::string progress_msg, actionlib::ServerGoalHandle< ActionSpec > &gh)
bool publishStatusPercentageDone(const std::string progress_msg, const unsigned percentage, actionlib::ServerGoalHandle< ActionSpec > &gh)
bool publishPercentageDone(const unsigned percentage, actionlib::ServerGoalHandle< ActionSpec > &gh)
PathPlanningAlgorithm(const std::string name, const std::string description, const std::string service_name)
actionlib_msgs::GoalStatus getGoalStatus() const
virtual ~PathPlanningAlgorithm()=0