path_planning_algorithm_imp.hpp
Go to the documentation of this file.
1 #ifndef RAM_PATH_PLANNING_PATH_PLANNING_ALGORITHM_IMP_HPP
2 #define RAM_PATH_PLANNING_PATH_PLANNING_ALGORITHM_IMP_HPP
3 
4 namespace ram_path_planning
5 {
6 template<class ActionSpec>
8  const std::string description,
9  const std::string service_name) :
10  name_(name),
11  description_(description),
12  service_name_(service_name)
13  {
14  }
15 
16 template<class ActionSpec>
18  {
19  }
20 
21 template<class ActionSpec>
24  {
25  ActionSpec action;
26  // Publish Feedback value
27  if (gh.getGoalStatus().status != actionlib_msgs::GoalStatus::ACTIVE)
28  return false;
29 
30  action.action_feedback.feedback.progress_value = percentage;
31  gh.publishFeedback(action.action_feedback.feedback);
32  return true;
33  }
34 
35 template<class ActionSpec>
36  bool PathPlanningAlgorithm<ActionSpec>::publishStatusDone(const std::string progress_msg,
38  {
39  ActionSpec action;
40  // Publish Feedback value
41  if (gh.getGoalStatus().status != actionlib_msgs::GoalStatus::ACTIVE)
42  return false;
43 
44  action.action_feedback.feedback.progress_msg = progress_msg;
45  gh.publishFeedback(action.action_feedback.feedback);
46  return true;
47 
48  }
49 
50 template<class ActionSpec>
52  const unsigned percentage,
54  {
55  ActionSpec action;
56  // Publish Feedback value
57  if (gh.getGoalStatus().status != actionlib_msgs::GoalStatus::ACTIVE)
58  return false;
59 
60  action.action_feedback.feedback.progress_value = percentage;
61  action.action_feedback.feedback.progress_msg = progress_msg;
62  gh.publishFeedback(action.action_feedback.feedback);
63  return true;
64 
65  }
66 
67 }
68 
69 #endif
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)
action
PathPlanningAlgorithm(const std::string name, const std::string description, const std::string service_name)
actionlib_msgs::GoalStatus getGoalStatus() const


ram_path_planning
Author(s): Andres Campos - Institut Maupertuis
autogenerated on Mon Jun 10 2019 14:50:03