controller_template.hpp
Go to the documentation of this file.
00001 #ifndef __CONTROLLER_TEMPLATE__
00002 #define __CONTROLLER_TEMPLATE__
00003 
00004 #include <actionlib/server/simple_action_server.h>
00005 #include <ros/package.h>
00006 #include <ros/ros.h>
00007 #include <sensor_msgs/JointState.h>
00008 #include <cmath>
00009 #include <generic_control_toolbox/bag_manager.hpp>
00010 
00011 namespace generic_control_toolbox
00012 {
00013 const double MAX_DT = 0.5;
00014 
00018 class ControllerBase
00019 {
00020  public:
00021   ControllerBase(ros::NodeHandle nh = ros::NodeHandle("~"));
00022   virtual ~ControllerBase();
00023 
00032   virtual sensor_msgs::JointState updateControl(
00033       const sensor_msgs::JointState &current_state,
00034       const ros::Duration &dt) = 0;
00035 
00042   virtual bool isActive() const = 0;
00043 
00047   virtual void resetInternalState() = 0;
00048 };
00049 
00054 template <class ActionClass, class ActionGoal, class ActionFeedback,
00055           class ActionResult>
00056 class ControllerTemplate : public ControllerBase
00057 {
00058  public:
00059   ControllerTemplate(const std::string &action_name,
00060                      ros::NodeHandle nh = ros::NodeHandle("~"));
00061   virtual ~ControllerTemplate();
00062 
00066   virtual sensor_msgs::JointState updateControl(
00067       const sensor_msgs::JointState &current_state, const ros::Duration &dt);
00068 
00069   virtual bool isActive() const;
00070 
00071   virtual void resetInternalState();
00072 
00073  protected:
00077   virtual sensor_msgs::JointState controlAlgorithm(
00078       const sensor_msgs::JointState &current_state,
00079       const ros::Duration &dt) = 0;
00080 
00087   virtual bool parseGoal(boost::shared_ptr<const ActionGoal> goal) = 0;
00088 
00092   virtual void resetController() = 0;
00093 
00103   sensor_msgs::JointState lastState(const sensor_msgs::JointState &current);
00104 
00105   boost::shared_ptr<actionlib::SimpleActionServer<ActionClass> > action_server_;
00106   ActionFeedback feedback_;
00107   ActionResult result_;
00108 
00109  private:
00114   void startActionlib();
00115 
00119   virtual bool goalCB();
00120 
00124   virtual void preemptCB();
00125 
00129   void resetFlags();
00130 
00131   std::string action_name_;
00132   ros::NodeHandle nh_;
00133   std::shared_ptr<BagManager> bag_manager_;
00134   sensor_msgs::JointState last_state_;
00135   bool has_state_, acquired_goal_;
00136 };
00137 
00138 template <class ActionClass, class ActionGoal, class ActionFeedback,
00139           class ActionResult>
00140 ControllerTemplate<ActionClass, ActionGoal, ActionFeedback, ActionResult>::
00141     ControllerTemplate(const std::string &action_name, ros::NodeHandle nh)
00142     : action_name_(action_name), nh_(nh)
00143 {
00144   resetFlags();
00145   startActionlib();
00146 }
00147 
00148 template <class ActionClass, class ActionGoal, class ActionFeedback,
00149           class ActionResult>
00150 sensor_msgs::JointState ControllerTemplate<
00151     ActionClass, ActionGoal, ActionFeedback,
00152     ActionResult>::updateControl(const sensor_msgs::JointState &current_state,
00153                                  const ros::Duration &dt)
00154 {
00155   if (!action_server_->isActive() || !acquired_goal_)
00156   {
00157     return lastState(current_state);
00158   }
00159 
00160   ROS_DEBUG_THROTTLE(10, "Calling %s control algorithm", action_name_.c_str());
00161   if (dt.toSec() > MAX_DT)  // lost communication for too much time
00162   {
00163     ROS_ERROR_STREAM(action_name_ << " did not receive updates for more than "
00164                                   << MAX_DT << " seconds, aborting");
00165     action_server_->setAborted(result_);
00166     return lastState(current_state);
00167   }
00168 
00169   sensor_msgs::JointState ret = controlAlgorithm(current_state, dt);
00170   action_server_->publishFeedback(feedback_);
00171 
00172   if (bag_manager_)
00173   {
00174     bag_manager_->write(feedback_);  // build log file
00175   }
00176 
00177   if (!action_server_->isActive())
00178   {
00179     resetInternalState();
00180     return lastState(current_state);
00181   }
00182 
00183   // verify sanity of values
00184   for (unsigned int i = 0; i < ret.name.size(); i++)
00185   {
00186     if (!std::isfinite(ret.position[i]) || !std::isfinite(ret.velocity[i]))
00187     {
00188       ROS_ERROR("Invalid joint states in %s", action_name_.c_str());
00189       return lastState(current_state);
00190     }
00191   }
00192 
00193   return ret;
00194 }
00195 
00196 template <class ActionClass, class ActionGoal, class ActionFeedback,
00197           class ActionResult>
00198 bool ControllerTemplate<ActionClass, ActionGoal, ActionFeedback,
00199                         ActionResult>::isActive() const
00200 {
00201   if (!action_server_->isActive())
00202   {
00203     return false;
00204   }
00205 
00206   return true;
00207 }
00208 
00209 template <class ActionClass, class ActionGoal, class ActionFeedback,
00210           class ActionResult>
00211 void ControllerTemplate<ActionClass, ActionGoal, ActionFeedback,
00212                         ActionResult>::resetInternalState()
00213 {
00214   if (action_server_->isActive())
00215   {
00216     action_server_->setAborted();
00217   }
00218 
00219   resetFlags();
00220   resetController();
00221 }
00222 
00223 template <class ActionClass, class ActionGoal, class ActionFeedback,
00224           class ActionResult>
00225 void ControllerTemplate<ActionClass, ActionGoal, ActionFeedback,
00226                         ActionResult>::resetFlags()
00227 {
00228   has_state_ = false;
00229   acquired_goal_ = false;
00230 
00231   if (bag_manager_)
00232   {
00233     bag_manager_.reset();
00234   }
00235 }
00236 
00237 template <class ActionClass, class ActionGoal, class ActionFeedback,
00238           class ActionResult>
00239 sensor_msgs::JointState ControllerTemplate<
00240     ActionClass, ActionGoal, ActionFeedback,
00241     ActionResult>::lastState(const sensor_msgs::JointState &current)
00242 {
00243   if (current.position.size() == 0)  // Invalid state
00244   {
00245     ROS_WARN("lastState got invalid state");
00246     return last_state_;
00247   }
00248 
00249   if (!has_state_)
00250   {
00251     last_state_ = current;
00252     for (unsigned long i = 0; i < last_state_.velocity.size(); i++)
00253     {
00254       last_state_.velocity[i] = 0.0;
00255     }
00256 
00257     has_state_ = true;
00258   }
00259 
00260   return last_state_;
00261 }
00262 
00263 template <class ActionClass, class ActionGoal, class ActionFeedback,
00264           class ActionResult>
00265 bool ControllerTemplate<ActionClass, ActionGoal, ActionFeedback,
00266                         ActionResult>::goalCB()
00267 {
00268   boost::shared_ptr<const ActionGoal> goal = action_server_->acceptNewGoal();
00269 
00270   if (!parseGoal(goal))
00271   {
00272     action_server_->setAborted(result_);
00273     return false;
00274   }
00275 
00276   acquired_goal_ = true;
00277 
00278   if (nh_.hasParam("record_bag"))  // controller is supposed to produce a log
00279   {
00280     std::string package_name, path, topic;
00281 
00282     topic = nh_.resolveName(action_name_) + std::string("/feedback");
00283 
00284     if (nh_.getParam("record_bag/package", package_name))
00285     {
00286       path = ros::package::getPath(package_name) + "/bags/";
00287       bag_manager_ = std::make_shared<BagManager>(path, topic);
00288     }
00289     else if (nh_.getParam("record_bag/path", path))
00290     {
00291       bag_manager_ = std::make_shared<BagManager>(path, topic);
00292     }
00293     else
00294     {
00295       ROS_WARN(
00296           "No record_bag/package or record_bag/path parameters detected! No "
00297           "bag will be recorded");
00298     }
00299   }
00300 
00301   ROS_INFO("New goal received in %s", action_name_.c_str());
00302   return true;
00303 }
00304 
00305 template <class ActionClass, class ActionGoal, class ActionFeedback,
00306           class ActionResult>
00307 void ControllerTemplate<ActionClass, ActionGoal, ActionFeedback,
00308                         ActionResult>::preemptCB()
00309 {
00310   action_server_->setPreempted(result_);
00311   ROS_WARN("%s preempted!", action_name_.c_str());
00312   resetInternalState();
00313 }
00314 
00315 template <class ActionClass, class ActionGoal, class ActionFeedback,
00316           class ActionResult>
00317 ControllerTemplate<ActionClass, ActionGoal, ActionFeedback,
00318                    ActionResult>::~ControllerTemplate()
00319 {
00320 }
00321 
00322 template <class ActionClass, class ActionGoal, class ActionFeedback,
00323           class ActionResult>
00324 void ControllerTemplate<ActionClass, ActionGoal, ActionFeedback,
00325                         ActionResult>::startActionlib()
00326 {
00327   // Initialize actionlib server
00328   action_server_ =
00329       boost::shared_ptr<actionlib::SimpleActionServer<ActionClass> >(
00330           new actionlib::SimpleActionServer<ActionClass>(nh_, action_name_,
00331                                                          false));
00332 
00333   // Register callbacks
00334   action_server_->registerGoalCallback(
00335       boost::bind(&ControllerTemplate::goalCB, this));
00336   action_server_->registerPreemptCallback(
00337       boost::bind(&ControllerTemplate::preemptCB, this));
00338 
00339   action_server_->start();
00340 
00341   ROS_INFO("%s initialized successfully!", action_name_.c_str());
00342 }
00343 
00344 typedef boost::shared_ptr<ControllerBase> BasePtr;
00345 }  // namespace generic_control_toolbox
00346 
00347 #endif


generic_control_toolbox
Author(s): diogo
autogenerated on Thu Jun 6 2019 18:02:57