callbacks_common.h
Go to the documentation of this file.
1 
29 #ifndef BEBOP_COMMON_COMMANDS_H
30 #define BEBOP_COMMON_COMMANDS_H
31 
32 #include <string>
33 #include <ros/ros.h>
34 #include <boost/thread/mutex.hpp>
35 #include <boost/thread/lock_guard.hpp>
36 
37 namespace bebop_driver
38 {
39 
40 // Forward decl
41 class BebopArdrone3Config;
42 
43 namespace cb
44 {
45 
46 /* Base class for All SDK Commands */
48 {
49 protected:
50  eARCONTROLLER_DICTIONARY_KEY cmd_key_;
51  ARCONTROLLER_DICTIONARY_ARG_t* arg;
52  mutable ::boost::mutex mutex_;
53 
54 public:
55  AbstractCommand(eARCONTROLLER_DICTIONARY_KEY cmd_key)
56  : cmd_key_(cmd_key), arg(NULL)
57  {}
58 
59  virtual ~AbstractCommand()
60  {}
61 
62  inline eARCONTROLLER_DICTIONARY_KEY GetCommandKey() const {return cmd_key_;}
63 
64  virtual void Update(const ARCONTROLLER_DICTIONARY_ARG_t* arg, const ::ros::Time& t) = 0;
65 };
66 
67 // This is not yet abstract
69 {
70 protected:
73 
74 public:
75  AbstractState(eARCONTROLLER_DICTIONARY_KEY cmd_key, const bool pub_enabled = false)
76  : AbstractCommand(cmd_key), pub_enabled_(pub_enabled)
77  {}
78 
79  virtual ~AbstractState()
80  {}
81 };
82 
84 {
85 protected:
87 
88 public:
89  AbstractSetting(eARCONTROLLER_DICTIONARY_KEY cmd_key, ros::NodeHandle& priv_nh)
90  : AbstractCommand(cmd_key), priv_nh_(priv_nh)
91  {}
92 
93  virtual ~AbstractSetting()
94  {}
95 
96  virtual void UpdateBebopFromROS(const BebopArdrone3Config &config, const ARCONTROLLER_Device_t* bebop_ctrl_ptr_) = 0;
97 
98 };
99 
100 } // namespace cb
101 } // namespace bebop_driver
102 
103 #endif // BEBOP_COMMON_COMMANDS_H
eARCONTROLLER_DICTIONARY_KEY GetCommandKey() const
eARCONTROLLER_DICTIONARY_KEY cmd_key_
geometry_msgs::TransformStamped t
virtual void Update(const ARCONTROLLER_DICTIONARY_ARG_t *arg, const ::ros::Time &t)=0
AbstractSetting(eARCONTROLLER_DICTIONARY_KEY cmd_key, ros::NodeHandle &priv_nh)
AbstractCommand(eARCONTROLLER_DICTIONARY_KEY cmd_key)
AbstractState(eARCONTROLLER_DICTIONARY_KEY cmd_key, const bool pub_enabled=false)
ARCONTROLLER_DICTIONARY_ARG_t * arg


bebop_driver
Author(s): Mani Monajjemi
autogenerated on Mon Jun 10 2019 12:58:56