humotion / src / server / controller.cpp @ 5e4bc615
History | View | Annotate | Download (8.837 KB)
1 | 8c6c1163 | Simon Schulz | /*
|
---|---|---|---|
2 | * This file is part of humotion
|
||
3 | *
|
||
4 | * Copyright(c) sschulz <AT> techfak.uni-bielefeld.de
|
||
5 | * http://opensource.cit-ec.de/projects/humotion
|
||
6 | *
|
||
7 | * This file may be licensed under the terms of the
|
||
8 | * GNU Lesser General Public License Version 3 (the ``LGPL''),
|
||
9 | * or (at your option) any later version.
|
||
10 | *
|
||
11 | * Software distributed under the License is distributed
|
||
12 | * on an ``AS IS'' basis, WITHOUT WARRANTY OF ANY KIND, either
|
||
13 | * express or implied. See the LGPL for the specific language
|
||
14 | * governing rights and limitations.
|
||
15 | *
|
||
16 | * You should have received a copy of the LGPL along with this
|
||
17 | * program. If not, go to http://www.gnu.org/licenses/lgpl.html
|
||
18 | * or write to the Free Software Foundation, Inc.,
|
||
19 | * 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, USA.
|
||
20 | *
|
||
21 | * The development of this software was supported by the
|
||
22 | * Excellence Cluster EXC 277 Cognitive Interaction Technology.
|
||
23 | * The Excellence Cluster EXC 277 is a grant of the Deutsche
|
||
24 | * Forschungsgemeinschaft (DFG) in the context of the German
|
||
25 | * Excellence Initiative.
|
||
26 | */
|
||
27 | |||
28 | 0c8d22a5 | sschulz | #include "humotion/server/controller.h" |
29 | #include "humotion/server/eye_motion_generator.h" |
||
30 | #include "humotion/server/eyebrow_motion_generator.h" |
||
31 | #include "humotion/server/eyelid_motion_generator.h" |
||
32 | #include "humotion/server/mouth_motion_generator.h" |
||
33 | #include "humotion/server/neck_motion_generator.h" |
||
34 | #include "humotion/timestamp.h" |
||
35 | |||
36 | // using namespace std;
|
||
37 | // using namespace humotion;
|
||
38 | // using namespace humotion::server;
|
||
39 | |||
40 | using humotion::server::Controller;
|
||
41 | 6d13138a | sschulz | using humotion::server::Config;
|
42 | 8c6c1163 | Simon Schulz | |
43 | //! constructor
|
||
44 | ea068cf1 | sschulz | Controller::Controller(JointInterface *j) { |
45 | activated_ = false;
|
||
46 | joint_interface_ = j; |
||
47 | 6d13138a | sschulz | |
48 | config_ = new Config();
|
||
49 | 8c6c1163 | Simon Schulz | } |
50 | |||
51 | //! destructor
|
||
52 | 0c8d22a5 | sschulz | Controller::~Controller() { |
53 | 8c6c1163 | Simon Schulz | } |
54 | |||
55 | //! initialise motion generators
|
||
56 | 0c8d22a5 | sschulz | void Controller::init_motion_generators() {
|
57 | // NOTE: the order of these generators is important!
|
||
58 | 8c6c1163 | Simon Schulz | // (i.e. the neck generator must be added after the eye generator!)
|
59 | |||
60 | 0c8d22a5 | sschulz | // eye motion generation:
|
61 | 6d13138a | sschulz | add_motion_generator(new EyeMotionGenerator(joint_interface_, config_));
|
62 | 8c6c1163 | Simon Schulz | |
63 | 0c8d22a5 | sschulz | // eyelid motion generator
|
64 | 6d13138a | sschulz | add_motion_generator(new EyelidMotionGenerator(joint_interface_, config_));
|
65 | 8c6c1163 | Simon Schulz | |
66 | 0c8d22a5 | sschulz | // neck motion generator
|
67 | 6d13138a | sschulz | add_motion_generator(new NeckMotionGenerator(joint_interface_, config_));
|
68 | 8c6c1163 | Simon Schulz | |
69 | 0c8d22a5 | sschulz | // mouth motion generator
|
70 | 6d13138a | sschulz | add_motion_generator(new MouthMotionGenerator(joint_interface_, config_));
|
71 | 8c6c1163 | Simon Schulz | |
72 | 0c8d22a5 | sschulz | // eyebrow motion generator
|
73 | 6d13138a | sschulz | add_motion_generator(new EyebrowMotionGenerator(joint_interface_, config_));
|
74 | 8c6c1163 | Simon Schulz | } |
75 | |||
76 | //! add a single motion genrator
|
||
77 | 0c8d22a5 | sschulz | void Controller::add_motion_generator(MotionGenerator *m) {
|
78 | ea068cf1 | sschulz | motion_generator_vector_.push_back(m); |
79 | 8c6c1163 | Simon Schulz | } |
80 | |||
81 | //! calculate target angles for all motion generators:
|
||
82 | 0c8d22a5 | sschulz | void Controller::calculate_targets() {
|
83 | Controller::motion_generator_vector_t::iterator it; |
||
84 | ea068cf1 | sschulz | for (it = motion_generator_vector_.begin(); it < motion_generator_vector_.end(); it++) {
|
85 | 8c6c1163 | Simon Schulz | (*it)->calculate_targets(); |
86 | } |
||
87 | } |
||
88 | |||
89 | //! publish all target angles to the devices:
|
||
90 | //! NOTE: this is done in an extra loop to have a low delay between consequent sets:
|
||
91 | 0c8d22a5 | sschulz | void Controller::publish_targets() {
|
92 | Controller::motion_generator_vector_t::iterator it; |
||
93 | ea068cf1 | sschulz | for (it = motion_generator_vector_.begin(); it < motion_generator_vector_.end(); it++) {
|
94 | 8c6c1163 | Simon Schulz | (*it)->publish_targets(); |
95 | } |
||
96 | } |
||
97 | |||
98 | 0c8d22a5 | sschulz | humotion::GazeState Controller::relative_gaze_to_absolute_gaze(humotion::GazeState relative) { |
99 | caf7373f | Simon Schulz | double pan, tilt, roll;
|
100 | 0c8d22a5 | sschulz | humotion::GazeState absolute_gaze = relative; |
101 | 89374d69 | Simon Schulz | |
102 | 0c8d22a5 | sschulz | // incoming gaze state wants to set a relative gaze angle
|
103 | // in order to calc the new absolute gaze, we need to go back
|
||
104 | // in time and find out where the head was pointing at that specific time:
|
||
105 | 32327f15 | Simon Schulz | Timestamp relative_target_timestamp = relative.timestamp; |
106 | 89374d69 | Simon Schulz | |
107 | 0c8d22a5 | sschulz | // check if this timestamp allows a valid conversion:
|
108 | Timestamp history_begin = |
||
109 | ea068cf1 | sschulz | joint_interface_->get_ts_position(JointInterface::ID_NECK_PAN).get_first_timestamp(); |
110 | 0c8d22a5 | sschulz | // Timestamp history_end =
|
111 | // joint_interface->get_ts_position(JointInterface::ID_NECK_PAN).get_last_timestamp();
|
||
112 | |||
113 | // printf("> incoming: %f, history is %f to %f\n",relative_target_timestamp.to_seconds(),
|
||
114 | // history_begin.to_seconds(), history_end.to_seconds());
|
||
115 | |||
116 | // our history keeps the last n elements in a timestamped list
|
||
117 | if ((relative_target_timestamp < history_begin) || (history_begin.is_null())) {
|
||
118 | // when the incoming data is older than that it makes no sense
|
||
119 | // to do any guesswork and try to calculate a valid absolute target
|
||
120 | // therefore we will use the last known targets (see below)
|
||
121 | // in case we did not see this timestamp before, show a warning:
|
||
122 | ea068cf1 | sschulz | if (last_known_absolute_timestamp_ != relative_target_timestamp) {
|
123 | 0c8d22a5 | sschulz | printf("> WARNING: restored/guessed absolute target for unknown timestamp %f "
|
124 | "[this should not happen]\n", relative_target_timestamp.to_seconds());
|
||
125 | ea068cf1 | sschulz | last_known_absolute_target_pan_ = 0.0; |
126 | last_known_absolute_target_tilt_ = 0.0; |
||
127 | last_known_absolute_target_roll_ = 0.0; |
||
128 | caf7373f | Simon Schulz | } |
129 | 0c8d22a5 | sschulz | } else {
|
130 | // all fine, we can reconstruct the absolute target
|
||
131 | // fetch head / camera pose during that timestamp
|
||
132 | ea068cf1 | sschulz | double neck_pan = joint_interface_->get_ts_position(
|
133 | 0c8d22a5 | sschulz | JointInterface::ID_NECK_PAN).get_interpolated_value(relative_target_timestamp); |
134 | ea068cf1 | sschulz | double eye_l_pan = joint_interface_->get_ts_position(
|
135 | 0c8d22a5 | sschulz | JointInterface::ID_EYES_LEFT_LR).get_interpolated_value(relative_target_timestamp); |
136 | ea068cf1 | sschulz | double eye_r_pan = joint_interface_->get_ts_position(
|
137 | 0c8d22a5 | sschulz | JointInterface::ID_EYES_RIGHT_LR).get_interpolated_value(relative_target_timestamp); |
138 | ea068cf1 | sschulz | last_known_absolute_target_pan_ = neck_pan + (eye_l_pan + eye_r_pan)/2.0; |
139 | caf7373f | Simon Schulz | //
|
140 | ea068cf1 | sschulz | double neck_tilt = joint_interface_->get_ts_position(
|
141 | 0c8d22a5 | sschulz | JointInterface::ID_NECK_TILT).get_interpolated_value(relative_target_timestamp); |
142 | ea068cf1 | sschulz | double eye_tilt = joint_interface_->get_ts_position(
|
143 | 0c8d22a5 | sschulz | JointInterface::ID_EYES_BOTH_UD).get_interpolated_value(relative_target_timestamp); |
144 | ea068cf1 | sschulz | last_known_absolute_target_tilt_ = neck_tilt + eye_tilt; |
145 | caf7373f | Simon Schulz | //
|
146 | ea068cf1 | sschulz | last_known_absolute_target_roll_ = joint_interface_->get_ts_position( |
147 | 0c8d22a5 | sschulz | JointInterface::ID_NECK_ROLL).get_interpolated_value(relative_target_timestamp); |
148 | |||
149 | // safe this timestamp as known:
|
||
150 | ea068cf1 | sschulz | last_known_absolute_timestamp_ = relative_target_timestamp; |
151 | caf7373f | Simon Schulz | } |
152 | |||
153 | ea068cf1 | sschulz | pan = last_known_absolute_target_pan_; |
154 | tilt = last_known_absolute_target_tilt_; |
||
155 | roll = last_known_absolute_target_roll_; |
||
156 | 89374d69 | Simon Schulz | |
157 | 0c8d22a5 | sschulz | // substract offsets
|
158 | caf7373f | Simon Schulz | pan -= relative.pan_offset; |
159 | d82702d2 | Sebastian Meyer zu Borgsen | tilt -= relative.tilt_offset; |
160 | roll -= relative.roll_offset; |
||
161 | |||
162 | 3d980d8f | Sebastian Meyer zu Borgsen | |
163 | 0c8d22a5 | sschulz | // build up absolute target
|
164 | 1c758459 | Simon Schulz | absolute_gaze.gaze_type = GazeState::GAZETYPE_ABSOLUTE; |
165 | 89374d69 | Simon Schulz | absolute_gaze.pan = pan + relative.pan; |
166 | absolute_gaze.tilt = tilt + relative.tilt; |
||
167 | absolute_gaze.roll = roll + relative.roll; |
||
168 | 0c8d22a5 | sschulz | printf("pan now = %4.1f, rel=%4.1f ===> %4.2f\n", pan, relative.pan, absolute_gaze.pan);
|
169 | printf("tilt now = %4.1f, rel=%4.1f ===> %4.2f\n", tilt, relative.tilt, absolute_gaze.tilt);
|
||
170 | 89374d69 | Simon Schulz | |
171 | 0c8d22a5 | sschulz | // FIXME: use ros TF for that calculation...
|
172 | // see http://wiki.ros.org/tf/Tutorials/Time%20travel%20with%20tf%20%28C%2B%2B%29
|
||
173 | // ros::Time past = now - ros::Duration(5.0);
|
||
174 | // listener.waitForTransform("/turtle2", now,J "/turtle1", past, "/world", ros::Duration(1.0));
|
||
175 | // listener.lookupTransform("/turtle2", now, "/turtle1", past, "/world", transform);
|
||
176 | // absolute_gaze.dump();
|
||
177 | caf7373f | Simon Schulz | |
178 | 89374d69 | Simon Schulz | return absolute_gaze;
|
179 | } |
||
180 | |||
181 | 5d7ba19c | Simon Schulz | //! activate controller
|
182 | 0c8d22a5 | sschulz | void Controller::set_activated(void) { |
183 | ea068cf1 | sschulz | activated_ = true;
|
184 | 5d7ba19c | Simon Schulz | } |
185 | 8c6c1163 | Simon Schulz | |
186 | //! update gaze target:
|
||
187 | //! \param GazeState with target values for the overall gaze
|
||
188 | 0c8d22a5 | sschulz | void Controller::set_gaze_target(humotion::GazeState new_gaze_target) {
|
189 | ea068cf1 | sschulz | if (!activated_) {
|
190 | 0c8d22a5 | sschulz | // not yet initialized, ignore incoming targets
|
191 | 5d7ba19c | Simon Schulz | return;
|
192 | } |
||
193 | |||
194 | 0c8d22a5 | sschulz | humotion::GazeState target_gaze; |
195 | // new_gaze_target.dump();
|
||
196 | 89374d69 | Simon Schulz | |
197 | 0c8d22a5 | sschulz | // relative or absolute gaze update?
|
198 | if (new_gaze_target.gaze_type == GazeState::GAZETYPE_RELATIVE) {
|
||
199 | // relative gaze target -> calculate target angles
|
||
200 | 89374d69 | Simon Schulz | target_gaze = relative_gaze_to_absolute_gaze(new_gaze_target); |
201 | 0c8d22a5 | sschulz | } else {
|
202 | // already absolute gaze, set this
|
||
203 | 89374d69 | Simon Schulz | target_gaze = new_gaze_target; |
204 | } |
||
205 | |||
206 | 0c8d22a5 | sschulz | Controller::motion_generator_vector_t::iterator it; |
207 | ea068cf1 | sschulz | for (it = motion_generator_vector_.begin(); it < motion_generator_vector_.end(); it++) {
|
208 | 89374d69 | Simon Schulz | (*it)->set_gaze_target(target_gaze); |
209 | 8c6c1163 | Simon Schulz | } |
210 | } |
||
211 | |||
212 | //! update mouth state:
|
||
213 | //! \param MouthState with target values for the mouth joints
|
||
214 | 0c8d22a5 | sschulz | void Controller::set_mouth_target(MouthState s) {
|
215 | ea068cf1 | sschulz | if (!activated_) {
|
216 | 0c8d22a5 | sschulz | // not yet initialized, ignore incoming targets
|
217 | 5d7ba19c | Simon Schulz | return;
|
218 | } |
||
219 | |||
220 | 0c8d22a5 | sschulz | Controller::motion_generator_vector_t::iterator it; |
221 | ea068cf1 | sschulz | for (it = motion_generator_vector_.begin(); it < motion_generator_vector_.end(); it++) {
|
222 | 8c6c1163 | Simon Schulz | (*it)->set_mouth_target(s); |
223 | } |
||
224 | } |
||
225 | 277050c7 | sschulz | |
226 | //! access the configuration
|
||
227 | Config* Controller::get_config() { |
||
228 | return config_;
|
||
229 | } |