callbacks_common.h
Go to the documentation of this file.
00001 
00029 #ifndef BEBOP_COMMON_COMMANDS_H
00030 #define BEBOP_COMMON_COMMANDS_H
00031 
00032 #include <string>
00033 #include <ros/ros.h>
00034 #include <boost/thread/mutex.hpp>
00035 #include <boost/thread/lock_guard.hpp>
00036 
00037 namespace bebop_driver
00038 {
00039 
00040 // Forward decl
00041 class BebopArdrone3Config;
00042 
00043 namespace cb
00044 {
00045 
00046 /* Base class for All SDK Commands */
00047 class AbstractCommand
00048 {
00049 protected:
00050   eARCONTROLLER_DICTIONARY_KEY cmd_key_;
00051   ARCONTROLLER_DICTIONARY_ARG_t* arg;
00052   mutable ::boost::mutex mutex_;
00053 
00054 public:
00055   AbstractCommand(eARCONTROLLER_DICTIONARY_KEY cmd_key)
00056     : cmd_key_(cmd_key), arg(NULL)
00057   {}
00058 
00059   virtual ~AbstractCommand()
00060   {}
00061 
00062   inline eARCONTROLLER_DICTIONARY_KEY GetCommandKey() const {return cmd_key_;}
00063 
00064   virtual void Update(const ARCONTROLLER_DICTIONARY_ARG_t* arg, const ::ros::Time& t) = 0;
00065 };
00066 
00067 // This is not yet abstract
00068 class AbstractState : public AbstractCommand
00069 {
00070 protected:
00071   bool pub_enabled_;
00072   ::ros::Publisher ros_pub_;
00073 
00074 public:
00075   AbstractState(eARCONTROLLER_DICTIONARY_KEY cmd_key, const bool pub_enabled = false)
00076     : AbstractCommand(cmd_key), pub_enabled_(pub_enabled)
00077   {}
00078 
00079   virtual ~AbstractState()
00080   {}
00081 };
00082 
00083 class AbstractSetting: public AbstractCommand
00084 {
00085 protected:
00086   ros::NodeHandle priv_nh_;
00087 
00088 public:
00089   AbstractSetting(eARCONTROLLER_DICTIONARY_KEY cmd_key, ros::NodeHandle& priv_nh)
00090     : AbstractCommand(cmd_key), priv_nh_(priv_nh)
00091   {}
00092 
00093   virtual ~AbstractSetting()
00094   {}
00095 
00096   virtual void UpdateBebopFromROS(const BebopArdrone3Config &config, const ARCONTROLLER_Device_t* bebop_ctrl_ptr_) = 0;
00097 
00098 };
00099 
00100 }  // namespace cb
00101 }  // namespace bebop_driver
00102 
00103 #endif  // BEBOP_COMMON_COMMANDS_H


bebop_driver
Author(s): Mani Monajjemi
autogenerated on Mon Aug 21 2017 02:36:39