sensor_updater.hpp
Go to the documentation of this file.
1 /*
2 * @file sensor_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 class is used to update the tactile sensor command.
22 *
23 *
24 */
25 
26 #ifndef SENSOR_UPDATER_HPP_
27 #define SENSOR_UPDATER_HPP_
28 
29 
30 #include <ros/ros.h>
31 #include <vector>
32 #include <list>
33 #include <queue>
35 
37 
38 extern "C"
39 {
42 }
43 
44 namespace generic_updater
45 {
46 /*
47 * The Sensor Updater builds the next command we want to send to the hand.
48 * We can ask for different types of data at different rates. The data and
49 * their rates are defined in the sr_ethercat_hand_config/rates/sensor_data_polling.yaml
50 * The important data are refreshed as often as possible (they have a -1. refresh
51 * rate in the config file).
52 *
53 * The unimportant data are refreshed at their given rate (the value is defined in
54 * the config in seconds).
55 */
56 template<class CommandType>
58  public GenericUpdater<CommandType>
59 {
60 public:
61  SensorUpdater(std::vector<UpdateConfig> update_configs_vector,
63 
64  /*
65  * Updates the initialization command to send to the hand. This function is called
66  * at each packCommand() call. Ask for the relevant information for the tactiles.
67  *
68  * @param command The command which will be sent to the palm.
69  * @return current update state
70  */
72 
73  /*
74  * Updates the command to send to the hand. This function is called
75  * at each packCommand() call. Ask for the relevant information for the tactiles.
76  * If an unimportant data is waiting then we send it, otherwise, we send the next
77  * important data.
78  *
79  * @param command The command which will be sent to the palm.
80  * @return current update state
81  */
83 
84  /*
85  * Will send the reset command to the tactiles, on next build
86  * command call.
87  *
88  * Simply adds the reset command to the unimportant_data_queue.
89  *
90  *
91  * @return true if RESET added to the top queue.
92  */
93  bool reset();
94 };
95 } // namespace generic_updater
96 
97 
98 /* For the emacs weenies in the crowd.
99 Local Variables:
100  c-basic-offset: 2
101 End:
102 */
103 
104 #endif /* SENSOR_UPDATER_HPP_ */
operation_mode::device_update_state::DeviceUpdateState update_state
std::vector< UpdateConfig > update_configs_vector
operation_mode::device_update_state::DeviceUpdateState build_init_command(CommandType *command)
ROSLIB_DECL std::string command(const std::string &cmd)
operation_mode::device_update_state::DeviceUpdateState build_command(CommandType *command)
SensorUpdater(std::vector< UpdateConfig > update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state)


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