controller_template.hpp
Go to the documentation of this file.
1 #ifndef __CONTROLLER_TEMPLATE__
2 #define __CONTROLLER_TEMPLATE__
3 
5 #include <ros/package.h>
6 #include <ros/ros.h>
7 #include <sensor_msgs/JointState.h>
8 #include <cmath>
10 
12 {
13 const double MAX_DT = 0.5;
14 
19 {
20  public:
22  virtual ~ControllerBase();
23 
32  virtual sensor_msgs::JointState updateControl(
33  const sensor_msgs::JointState &current_state,
34  const ros::Duration &dt) = 0;
35 
42  virtual bool isActive() const = 0;
43 
47  virtual void resetInternalState() = 0;
48 };
49 
54 template <class ActionClass, class ActionGoal, class ActionFeedback,
55  class ActionResult>
57 {
58  public:
59  ControllerTemplate(const std::string &action_name,
61  virtual ~ControllerTemplate();
62 
66  virtual sensor_msgs::JointState updateControl(
67  const sensor_msgs::JointState &current_state, const ros::Duration &dt);
68 
69  virtual bool isActive() const;
70 
71  virtual void resetInternalState();
72 
73  protected:
77  virtual sensor_msgs::JointState controlAlgorithm(
78  const sensor_msgs::JointState &current_state,
79  const ros::Duration &dt) = 0;
80 
87  virtual bool parseGoal(boost::shared_ptr<const ActionGoal> goal) = 0;
88 
92  virtual void resetController() = 0;
93 
103  sensor_msgs::JointState lastState(const sensor_msgs::JointState &current);
104 
106  ActionFeedback feedback_;
107  ActionResult result_;
108 
109  private:
114  void startActionlib();
115 
119  virtual bool goalCB();
120 
124  virtual void preemptCB();
125 
129  void resetFlags();
130 
131  std::string action_name_;
133  std::shared_ptr<BagManager> bag_manager_;
134  sensor_msgs::JointState last_state_;
135  bool has_state_, acquired_goal_;
136 };
137 
138 template <class ActionClass, class ActionGoal, class ActionFeedback,
139  class ActionResult>
141  ControllerTemplate(const std::string &action_name, ros::NodeHandle nh)
142  : action_name_(action_name), nh_(nh)
143 {
144  resetFlags();
145  startActionlib();
146 }
147 
148 template <class ActionClass, class ActionGoal, class ActionFeedback,
149  class ActionResult>
150 sensor_msgs::JointState ControllerTemplate<
151  ActionClass, ActionGoal, ActionFeedback,
152  ActionResult>::updateControl(const sensor_msgs::JointState &current_state,
153  const ros::Duration &dt)
154 {
155  if (!action_server_->isActive() || !acquired_goal_)
156  {
157  return lastState(current_state);
158  }
159 
160  ROS_DEBUG_THROTTLE(10, "Calling %s control algorithm", action_name_.c_str());
161  if (dt.toSec() > MAX_DT) // lost communication for too much time
162  {
163  ROS_ERROR_STREAM(action_name_ << " did not receive updates for more than "
164  << MAX_DT << " seconds, aborting");
165  action_server_->setAborted(result_);
166  return lastState(current_state);
167  }
168 
169  sensor_msgs::JointState ret = controlAlgorithm(current_state, dt);
170  action_server_->publishFeedback(feedback_);
171 
172  if (bag_manager_)
173  {
174  bag_manager_->write(feedback_); // build log file
175  }
176 
177  if (!action_server_->isActive())
178  {
180  return lastState(current_state);
181  }
182 
183  // verify sanity of values
184  for (unsigned int i = 0; i < ret.name.size(); i++)
185  {
186  if (!std::isfinite(ret.position[i]) || !std::isfinite(ret.velocity[i]))
187  {
188  ROS_ERROR("Invalid joint states in %s", action_name_.c_str());
189  return lastState(current_state);
190  }
191  }
192 
193  return ret;
194 }
195 
196 template <class ActionClass, class ActionGoal, class ActionFeedback,
197  class ActionResult>
198 bool ControllerTemplate<ActionClass, ActionGoal, ActionFeedback,
199  ActionResult>::isActive() const
200 {
201  if (!action_server_->isActive())
202  {
203  return false;
204  }
205 
206  return true;
207 }
208 
209 template <class ActionClass, class ActionGoal, class ActionFeedback,
210  class ActionResult>
211 void ControllerTemplate<ActionClass, ActionGoal, ActionFeedback,
212  ActionResult>::resetInternalState()
213 {
214  if (action_server_->isActive())
215  {
216  action_server_->setAborted();
217  }
218 
219  resetFlags();
220  resetController();
221 }
222 
223 template <class ActionClass, class ActionGoal, class ActionFeedback,
224  class ActionResult>
225 void ControllerTemplate<ActionClass, ActionGoal, ActionFeedback,
226  ActionResult>::resetFlags()
227 {
228  has_state_ = false;
229  acquired_goal_ = false;
230 
231  if (bag_manager_)
232  {
233  bag_manager_.reset();
234  }
235 }
236 
237 template <class ActionClass, class ActionGoal, class ActionFeedback,
238  class ActionResult>
239 sensor_msgs::JointState ControllerTemplate<
240  ActionClass, ActionGoal, ActionFeedback,
241  ActionResult>::lastState(const sensor_msgs::JointState &current)
242 {
243  if (current.position.size() == 0) // Invalid state
244  {
245  ROS_WARN("lastState got invalid state");
246  return last_state_;
247  }
248 
249  if (!has_state_)
250  {
251  last_state_ = current;
252  for (unsigned long i = 0; i < last_state_.velocity.size(); i++)
253  {
254  last_state_.velocity[i] = 0.0;
255  }
256 
257  has_state_ = true;
258  }
259 
260  return last_state_;
261 }
262 
263 template <class ActionClass, class ActionGoal, class ActionFeedback,
264  class ActionResult>
265 bool ControllerTemplate<ActionClass, ActionGoal, ActionFeedback,
266  ActionResult>::goalCB()
267 {
268  boost::shared_ptr<const ActionGoal> goal = action_server_->acceptNewGoal();
269 
270  if (!parseGoal(goal))
271  {
272  action_server_->setAborted(result_);
273  return false;
274  }
275 
276  acquired_goal_ = true;
277 
278  if (nh_.hasParam("record_bag")) // controller is supposed to produce a log
279  {
280  std::string package_name, path, topic;
281 
282  topic = nh_.resolveName(action_name_) + std::string("/feedback");
283 
284  if (nh_.getParam("record_bag/package", package_name))
285  {
286  path = ros::package::getPath(package_name) + "/bags/";
287  bag_manager_ = std::make_shared<BagManager>(path, topic);
288  }
289  else if (nh_.getParam("record_bag/path", path))
290  {
291  bag_manager_ = std::make_shared<BagManager>(path, topic);
292  }
293  else
294  {
295  ROS_WARN(
296  "No record_bag/package or record_bag/path parameters detected! No "
297  "bag will be recorded");
298  }
299  }
300 
301  ROS_INFO("New goal received in %s", action_name_.c_str());
302  return true;
303 }
304 
305 template <class ActionClass, class ActionGoal, class ActionFeedback,
306  class ActionResult>
307 void ControllerTemplate<ActionClass, ActionGoal, ActionFeedback,
308  ActionResult>::preemptCB()
309 {
310  action_server_->setPreempted(result_);
311  ROS_WARN("%s preempted!", action_name_.c_str());
313 }
314 
315 template <class ActionClass, class ActionGoal, class ActionFeedback,
316  class ActionResult>
317 ControllerTemplate<ActionClass, ActionGoal, ActionFeedback,
318  ActionResult>::~ControllerTemplate()
319 {
320 }
321 
322 template <class ActionClass, class ActionGoal, class ActionFeedback,
323  class ActionResult>
324 void ControllerTemplate<ActionClass, ActionGoal, ActionFeedback,
325  ActionResult>::startActionlib()
326 {
327  // Initialize actionlib server
331  false));
332 
333  // Register callbacks
334  action_server_->registerGoalCallback(
335  boost::bind(&ControllerTemplate::goalCB, this));
336  action_server_->registerPreemptCallback(
337  boost::bind(&ControllerTemplate::preemptCB, this));
338 
339  action_server_->start();
340 
341  ROS_INFO("%s initialized successfully!", action_name_.c_str());
342 }
343 
345 } // namespace generic_control_toolbox
346 
347 #endif
sensor_msgs::JointState lastState(const sensor_msgs::JointState &current)
ControllerTemplate(const std::string &action_name, ros::NodeHandle nh=ros::NodeHandle("~"))
std::string resolveName(const std::string &name, bool remap=true) const
ControllerBase(ros::NodeHandle nh=ros::NodeHandle("~"))
#define ROS_WARN(...)
#define ROS_INFO(...)
boost::shared_ptr< ControllerBase > BasePtr
ROSLIB_DECL std::string getPath(const std::string &package_name)
boost::shared_ptr< actionlib::SimpleActionServer< ActionClass > > action_server_
virtual sensor_msgs::JointState updateControl(const sensor_msgs::JointState &current_state, const ros::Duration &dt)=0
bool getParam(const std::string &key, std::string &s) const
bool hasParam(const std::string &key) const
virtual bool parseGoal(boost::shared_ptr< const ActionGoal > goal)=0
#define ROS_ERROR_STREAM(args)
virtual sensor_msgs::JointState controlAlgorithm(const sensor_msgs::JointState &current_state, const ros::Duration &dt)=0
#define ROS_ERROR(...)
#define ROS_DEBUG_THROTTLE(period,...)
virtual sensor_msgs::JointState updateControl(const sensor_msgs::JointState &current_state, const ros::Duration &dt)


generic_control_toolbox
Author(s): diogo
autogenerated on Thu Jun 6 2019 19:54:44