generic_updater.hpp
Go to the documentation of this file.
1 /*
2 * @file generic_updater.hpp
3 * @author toni <toni@shadowrobot.com>
4 * @date 20 Oct 2011
5 *
6 /* Copyright 2011 Shadow Robot Company Ltd.
7 *
8 * This program is free software: you can redistribute it and/or modify it
9 * under the terms of the GNU General Public License as published by the Free
10 * Software Foundation version 2 of the License.
11 *
12 * This program is distributed in the hope that it will be useful, but WITHOUT
13 * ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
14 * FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
15 * more details.
16 *
17 * You should have received a copy of the GNU General Public License along
18 * with this program. If not, see <http://www.gnu.org/licenses/>.
19 *
20 *
21 * @brief This is a generic command updater: it has 2 different queues one for
22 * the important data which is updated as fast as possible, one for
23 * unimportant data which is updated on a time basis.
24 *
25 *
26 */
27 
28 #ifndef GENERIC_UPDATER_HPP_
29 #define GENERIC_UPDATER_HPP_
30 
31 #include <ros/ros.h>
32 #include <vector>
33 #include <list>
34 #include <queue>
35 #include <boost/thread/mutex.hpp>
36 #include <boost/smart_ptr.hpp>
38 
39 extern "C"
40 {
45 }
46 
47 namespace operation_mode
48 {
49 namespace device_update_state
50 {
52  {
55  };
56 } // namespace device_update_state
57 } // namespace operation_mode
58 
59 namespace generic_updater
60 {
62 {
65 };
66 
67 /*
68 * The Generic Updater builds the next command we want to send to the hand.
69 * We can ask for different types of data at different rates. The data and
70 * their rates are defined in the sr_ethercat_hand_config/rates/xxxxx.yaml
71 * The important data are refreshed as often as possible (they have a -1. refresh
72 * rate in the config file).
73 *
74 * The unimportant data are refreshed at their given rate (the value is defined in
75 * the config in seconds).
76 */
77 template<class CommandType>
79 {
80 public:
81  GenericUpdater(std::vector<UpdateConfig> update_configs_vector,
83 
84  virtual ~GenericUpdater()
85  {
86  }
87 
88  /*
89  * Building the motor command. This function is called at each packCommand() call.
90  * If an unimportant data is waiting then we send it, otherwise, we send the next
91  * important data.
92  *
93  * @param command The command which will be sent to the motor.
94  * @return the current state of the device.
95  */
96  virtual operation_mode::device_update_state::DeviceUpdateState build_command(CommandType *command) = 0;
97 
98  /*
99  * A timer callback for the unimportant data. The frequency of this callback
100  * is defined in the config file.
101  *
102  * @param event
103  * @param data_type The unimportant data type we want to ask for.
104  */
105  void timer_callback(const ros::TimerEvent &event, int32u data_type);
106 
108  // Contains all the initialization data types.
109  std::vector<UpdateConfig> initialization_configs_vector;
110 
112  std::vector<UpdateConfig> important_update_configs_vector;
113 
114 protected:
116 
119 
120  // All the timers for the unimportant data types.
121  std::vector<ros::Timer> timers;
122  // A queue containing the unimportant data types we want to ask for next time (empty most of the time).
123  std::queue<int32u, std::list<int32u> > unimportant_data_queue;
124  // Contains the vector with the update configs for every command. We store it to be able to reinitialize.
125  std::vector<UpdateConfig> update_configs_vector;
126 
128 };
129 } // namespace generic_updater
130 
131 
132 /* For the emacs weenies in the crowd.
133 Local Variables:
134  c-basic-offset: 2
135 End:
136 */
137 
138 #endif /* GENERIC_UPDATER_HPP_ */
std::queue< int32u, std::list< int32u > > unimportant_data_queue
int which_data_to_request
iterate through the important or initialization data types.
operation_mode::device_update_state::DeviceUpdateState update_state
boost::shared_ptr< boost::mutex > mutex
std::vector< ros::Timer > timers
std::vector< UpdateConfig > update_configs_vector
unsigned int int32u
ROSLIB_DECL std::string command(const std::string &cmd)
std::vector< UpdateConfig > initialization_configs_vector
std::vector< UpdateConfig > important_update_configs_vector
Contains all the important data types.


sr_robot_lib
Author(s): Ugo Cupcic, Toni Oliver
autogenerated on Tue Oct 13 2020 04:01:57