motor_updater.hpp
Go to the documentation of this file.
1 /*
2 * @file motor_updater.hpp
3 * @author Ugo Cupcic <ugo@shadowrobot.com>, <contact@shadowrobot.com>
4 * @date Tue Jun 7 09:15:21 2011
5 *
6 *
7 /* Copyright 2011 Shadow Robot Company Ltd.
8 *
9 * This program is free software: you can redistribute it and/or modify it
10 * under the terms of the GNU General Public License as published by the Free
11 * Software Foundation version 2 of the License.
12 *
13 * This program is distributed in the hope that it will be useful, but WITHOUT
14 * ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
15 * FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
16 * more details.
17 *
18 * You should have received a copy of the GNU General Public License along
19 * with this program. If not, see <http://www.gnu.org/licenses/>.
20 *
21 *
22 * @brief This contains a class used to determin which data we should ask the motor for,
23 * depending on the config we're using.
24 *
25 *
26 */
27 
28 #ifndef _MOTOR_UPDATER_HPP_
29 #define _MOTOR_UPDATER_HPP_
30 
31 #include <ros/ros.h>
32 #include <vector>
33 #include <list>
34 #include <queue>
35 #include <boost/smart_ptr.hpp>
37 
39 
40 extern "C"
41 {
44 }
45 
46 namespace generic_updater
47 {
48 /*
49 * The Motor Updater builds the next command we want to send to the hand.
50 * We can ask for different types of data at different rates. The data and
51 * their rates are defined in the sr_ethercat_hand_config/rates/motor_data_polling.yaml
52 * The important data are refreshed as often as possible (they have a -1. refresh
53 * rate in the config file).
54 *
55 * The unimportant data are refreshed at their given rate (the value is defined in
56 * the config in seconds).
57 */
58 template<class CommandType>
59 class MotorUpdater :
60  public GenericUpdater<CommandType>
61 {
62 public:
63  MotorUpdater(std::vector<UpdateConfig> update_configs_vector,
65 
66  /*
67  * Building the motor initialization command. This function is called at each packCommand() call.
68  * It builds initialization commands if the update state is operation_mode::device_update_state::INITIALIZATION.
69  *
70  * @param command The command which will be sent to the motor.
71  * @return the current update state of the motor update
72  */
74 
75  /*
76  * Building the motor command. This function is called at each packCommand() call.
77  * If an unimportant data is waiting then we send it, otherwise, we send the next
78  * important data.
79  *
80  * @param command The command which will be sent to the motor.
81  * @return the current update state of the motor update
82  */
84 
85 private:
86  // are we sending the command to the even or the uneven motors.
88 };
89 } // namespace generic_updater
90 
91 
92 /* For the emacs weenies in the crowd.
93  Local Variables:
94  c-basic-offset: 2
95  End:
96 */
97 
98 #endif
operation_mode::device_update_state::DeviceUpdateState update_state
operation_mode::device_update_state::DeviceUpdateState build_init_command(CommandType *command)
operation_mode::device_update_state::DeviceUpdateState build_command(CommandType *command)
std::vector< UpdateConfig > update_configs_vector
ROSLIB_DECL std::string command(const std::string &cmd)
MotorUpdater(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