Revision 0c8d22a5
.gitignore | ||
---|---|---|
1 |
*.user |
|
2 |
*.user.* |
|
3 |
build* |
CMakeLists.txt | ||
---|---|---|
83 | 83 |
## Your package locations should be listed before other locations |
84 | 84 |
include_directories(BEFORE ${Boost_INCLUDE_DIRS} ${REFLEXXES_INCLUDE_DIRS}) |
85 | 85 |
include_directories(BEFORE include) |
86 |
include_directories(BEFORE include/humotion) |
|
86 |
|
|
87 | 87 |
#make sure to use ros messages from current build |
88 | 88 |
include_directories(BEFORE ${CATKIN_DEVEL_PREFIX}/include) |
89 |
|
|
89 | 90 |
#this should be appended: |
90 | 91 |
include_directories(${catkin_INCLUDE_DIRS}) |
91 |
#link_directories (${Boost_LIBRARY_DIRS} ${REFLEXXES_LIBRARY_DIRS} ${catkin_LIBRARY_DIRS}) |
|
92 |
|
|
93 |
##################### |
|
94 |
# PLEASE DO NOT REMOVE THIS! This is a hack necessary for qtcreator to show cmake header files in the project view! |
|
95 |
file(GLOB DUMMY_HEADER_LIST RELATIVE ${CMAKE_CURRENT_SOURCE_DIR} include/humotion/*.h include/humotion/client/*.h include/humotion/server/*.h srv/*.srv msg/*.msg etc/*) |
|
96 | 92 |
|
93 |
#link_directories (${Boost_LIBRARY_DIRS} ${REFLEXXES_LIBRARY_DIRS} ${catkin_LIBRARY_DIRS}) |
|
97 | 94 |
|
98 | 95 |
## Declare a cpp library |
99 | 96 |
add_library(humotion |
... | ... | |
120 | 117 |
src/server/neck_motion_generator.cpp |
121 | 118 |
src/timestamp.cpp |
122 | 119 |
src/timestamped_list.cpp |
123 |
${DUMMY_HEADER_LIST} |
|
124 | 120 |
) |
125 | 121 |
|
126 | 122 |
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++0x") |
... | ... | |
186 | 182 |
|
187 | 183 |
#finally build (some) examples |
188 | 184 |
#add_subdirectory(./examples) |
185 |
|
|
186 |
|
|
187 |
################# |
|
188 |
## style guide ## |
|
189 |
################# |
|
190 |
set(ENABLE_CPPLINT 1) |
|
191 |
include(${CMAKE_CURRENT_SOURCE_DIR}/stylecheck/CpplintWrapper.cmake) |
|
192 |
CPPLINT_RECURSIVE(cpplint_include |
|
193 |
${CMAKE_CURRENT_SOURCE_DIR}/include |
|
194 |
${CMAKE_CURRENT_SOURCE_DIR}/include |
|
195 |
${CMAKE_CURRENT_BINARY_DIR}/include) |
|
196 |
CPPLINT_RECURSIVE(cpplint_src |
|
197 |
${CMAKE_CURRENT_SOURCE_DIR}/src |
|
198 |
${CMAKE_CURRENT_SOURCE_DIR}/src |
|
199 |
${CMAKE_CURRENT_BINARY_DIR}/src) |
|
200 |
add_dependencies(humotion cpplint_src cpplint_include) |
|
201 |
|
|
202 |
#workaround for qtcreator ide integration. do not remove! |
|
203 |
file(GLOB_RECURSE NODE_DUMMY_TARGETS RELATIVE ${CMAKE_CURRENT_SOURCE_DIR} *.h *.cfg *.yaml *.xml *.launch) |
|
204 |
add_custom_target(_dummy_target SOURCES ${NODE_DUMMY_TARGETS}) |
examples/yarp_icub/CMakeLists.txt | ||
---|---|---|
27 | 27 |
INSTALL(TARGETS ${MAIN} DESTINATION bin) |
28 | 28 |
|
29 | 29 |
|
30 |
############# |
|
30 |
#################
|
|
31 | 31 |
## style guide ## |
32 |
############# |
|
32 |
#################
|
|
33 | 33 |
set(ENABLE_CPPLINT 1) |
34 | 34 |
include(${CMAKE_CURRENT_SOURCE_DIR}/../../stylecheck/CpplintWrapper.cmake) |
35 | 35 |
CPPLINT_RECURSIVE(cpplint_include |
examples/yarp_icub/CMakeLists.txt.user | ||
---|---|---|
1 | 1 |
<?xml version="1.0" encoding="UTF-8"?> |
2 | 2 |
<!DOCTYPE QtCreatorProject> |
3 |
<!-- Written by QtCreator 3.0.1, 2016-02-16T14:14:22. -->
|
|
3 |
<!-- Written by QtCreator 3.0.1, 2016-02-18T16:12:37. -->
|
|
4 | 4 |
<qtcreator> |
5 | 5 |
<data> |
6 | 6 |
<variable>ProjectExplorer.Project.ActiveTarget</variable> |
... | ... | |
53 | 53 |
<valuemap type="QVariantMap"> |
54 | 54 |
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DefaultDisplayName">Desktop</value> |
55 | 55 |
<value type="QString" key="ProjectExplorer.ProjectConfiguration.DisplayName">Desktop</value> |
56 |
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">{0ff36a7d-682d-4601-a9c1-275f77eefc70}</value>
|
|
56 |
<value type="QString" key="ProjectExplorer.ProjectConfiguration.Id">{3152ed58-41d1-426c-b17f-dbe12171436a}</value>
|
|
57 | 57 |
<value type="int" key="ProjectExplorer.Target.ActiveBuildConfiguration">0</value> |
58 | 58 |
<value type="int" key="ProjectExplorer.Target.ActiveDeployConfiguration">0</value> |
59 | 59 |
<value type="int" key="ProjectExplorer.Target.ActiveRunConfiguration">0</value> |
60 | 60 |
<valuemap type="QVariantMap" key="ProjectExplorer.Target.BuildConfiguration.0"> |
61 | 61 |
<value type="bool" key="CMakeProjectManager.CMakeBuildConfiguration.UseNinja">false</value> |
62 | 62 |
<value type="QString" key="CMakeProjectManager.CMakeBuildConfiguration.UserArguments">-DCMAKE_INSTALL_PREFIX=/vol/icub/sschulz/releases/roman16-humotion-nightly/</value> |
63 |
<value type="QString" key="ProjectExplorer.BuildConfiguration.BuildDirectory">/homes/sschulz/src/flobi/humotion/examples/hum </value>
|
|
63 |
<value type="QString" key="ProjectExplorer.BuildConfiguration.BuildDirectory">/homes/sschulz/src/flobidev.core/humotion/examples/yarp_icub/build</value>
|
|
64 | 64 |
<valuemap type="QVariantMap" key="ProjectExplorer.BuildConfiguration.BuildStepList.0"> |
65 | 65 |
<valuemap type="QVariantMap" key="ProjectExplorer.BuildStepList.Step.0"> |
66 | 66 |
<value type="QString" key="CMakeProjectManager.MakeStep.AdditionalArguments"></value> |
... | ... | |
175 | 175 |
</data> |
176 | 176 |
<data> |
177 | 177 |
<variable>ProjectExplorer.Project.Updater.EnvironmentId</variable> |
178 |
<value type="QByteArray">{44110186-3313-405d-bf42-c546b33c1fcb}</value>
|
|
178 |
<value type="QByteArray">{ccede451-c1b6-4b92-a13d-14bd6a65dd35}</value>
|
|
179 | 179 |
</data> |
180 | 180 |
<data> |
181 | 181 |
<variable>ProjectExplorer.Project.Updater.FileVersion</variable> |
examples/yarp_icub/include/humotion_yarp_icub/icub_faceinterface.h | ||
---|---|---|
50 | 50 |
int previous_mouth_state; |
51 | 51 |
double target_angle_previous[iCubJointInterface::ICUB_JOINT_ID_ENUM_SIZE]; |
52 | 52 |
std::string scope; |
53 |
yarp::os::BufferedPort<yarp::os::Bottle> emotion_port[4];
|
|
53 |
yarp::os::BufferedPort<yarp::os::Bottle> emotion_port; |
|
54 | 54 |
}; |
55 | 55 |
|
56 | 56 |
#endif // EXAMPLES_HUMOTION_YARP_ICUB_INCLUDE_HUMOTION_YARP_ICUB_ICUB_FACEINTERFACE_H_ |
examples/yarp_icub/src/icub_faceinterface.cpp | ||
---|---|---|
28 | 28 |
#include "humotion_yarp_icub/icub_faceinterface.h" |
29 | 29 |
|
30 | 30 |
#include <boost/format.hpp> |
31 |
#include <boost/lexical_cast.hpp> |
|
32 |
|
|
33 | 31 |
#include <algorithm> |
34 | 32 |
#include <string> |
35 | 33 |
|
... | ... | |
48 | 46 |
cout << "opening connection to '"<< emotion_scope << "'\n"; |
49 | 47 |
|
50 | 48 |
bool init_ok = true; |
51 |
for (int i = 0; i < 4; i++) { |
|
52 |
// strange, if we use one output port only the first command is executed?! flushing issues? |
|
53 |
std::string emotion_port_out = "/emotionwriter" + boost::lexical_cast<std::string>(i); |
|
54 |
if (!emotion_port[i].open(emotion_port_out.c_str())) { |
|
55 |
cerr << "ERROR: failed to open emotion port '" << emotion_port_out << "'\n"; |
|
56 |
init_ok = false; |
|
57 |
} |
|
58 |
if (!Network::connect(emotion_port_out.c_str(), emotion_scope.c_str())) { |
|
59 |
cerr << "ERROR: failed to connect to emotion port '" << emotion_port_out << "'\n"; |
|
60 |
init_ok = false; |
|
61 |
} |
|
49 |
// open emotion port |
|
50 |
std::string emotion_port_out = "/emotionwriter"; |
|
51 |
if (!emotion_port.open(emotion_port_out.c_str())) { |
|
52 |
cerr << "ERROR: failed to open emotion port '" << emotion_port_out << "'\n"; |
|
53 |
init_ok = false; |
|
54 |
} |
|
55 |
if (!Network::connect(emotion_port_out.c_str(), emotion_scope.c_str())) { |
|
56 |
cerr << "ERROR: failed to connect to emotion port '" << emotion_port_out << "'\n"; |
|
57 |
init_ok = false; |
|
62 | 58 |
} |
63 | 59 |
|
64 | 60 |
if (!init_ok) { |
... | ... | |
76 | 72 |
//! special command to set eyelid angle |
77 | 73 |
//! \param angle in degrees |
78 | 74 |
void iCubFaceInterface::set_eyelid_angle(float angle) { |
79 |
if (emotion_port[0].getOutputCount() > 0) {
|
|
75 |
if (emotion_port.getOutputCount() > 0) { |
|
80 | 76 |
// try to set the value based on the upper one |
81 | 77 |
// some guesses from the sim: S30 = 0° / S40 = 10° |
82 | 78 |
int opening = (25.0 + 0.8*angle); |
... | ... | |
94 | 90 |
snprintf(buf, sizeof(buf), "S%2d", opening); |
95 | 91 |
|
96 | 92 |
// cout << "SETTING EYELID '" << buf << "' (" << angle << " -> " << opening << "\n"; |
97 |
Bottle &cmd = emotion_port[0].prepare();
|
|
93 |
Bottle &cmd = emotion_port.prepare(); |
|
98 | 94 |
cmd.clear(); |
99 | 95 |
cmd.addString(buf); |
100 |
emotion_port[0].writeStrict(); |
|
96 |
// NOTE: writeStrict is important in order not to loose packets |
|
97 |
emotion_port.writeStrict(); |
|
101 | 98 |
} else { |
102 | 99 |
cerr << "ERROR: no icub emotion output\n"; |
103 | 100 |
exit(EXIT_FAILURE); |
... | ... | |
108 | 105 |
//! \param id {0=left, 1=right) |
109 | 106 |
//! \param angle in degrees |
110 | 107 |
void iCubFaceInterface::set_eyebrow_angle(int id, float *target_angle) { |
111 |
int port_id; |
|
112 |
if (id == iCubJointInterface::ICUB_ID_EYES_LEFT_BROW) { |
|
113 |
port_id = 1; |
|
114 |
} else { |
|
115 |
port_id = 2; |
|
116 |
} |
|
117 | 108 |
|
118 |
if (emotion_port[port_id].getOutputCount() > 0) {
|
|
109 |
if (emotion_port.getOutputCount() > 0) { |
|
119 | 110 |
double angle = target_angle[id]; |
120 | 111 |
int icub_val = 0; |
121 | 112 |
|
... | ... | |
152 | 143 |
cmd_s = "R0" + boost::lexical_cast<std::string>(icub_val); |
153 | 144 |
} |
154 | 145 |
|
155 |
cout << "SETTING EYEBROW " << id << " (" << angle << " -> " << cmd_s << ")\n"; |
|
146 |
// cout << "SETTING EYEBROW " << id << " (" << angle << " -> " << cmd_s << ")\n";
|
|
156 | 147 |
|
157 |
Bottle &cmd = emotion_port[port_id].prepare();
|
|
148 |
Bottle &cmd = emotion_port.prepare(); |
|
158 | 149 |
cmd.clear(); |
159 | 150 |
cmd.addString(cmd_s); |
160 |
emotion_port[port_id].writeStrict(); |
|
151 |
// NOTE: writeStrict is important in order not to loose packets |
|
152 |
emotion_port.writeStrict(); |
|
161 | 153 |
} else { |
162 | 154 |
cerr << "ERROR: no icub emotion output\n"; |
163 | 155 |
exit(EXIT_FAILURE); |
... | ... | |
244 | 236 |
*/ |
245 | 237 |
|
246 | 238 |
// add mouth |
247 |
Bottle &cmd = emotion_port[3].prepare();
|
|
239 |
Bottle &cmd = emotion_port.prepare(); |
|
248 | 240 |
cmd.clear(); |
249 | 241 |
cmd.addString(buf); |
250 |
emotion_port[3].writeStrict(); |
|
242 |
// NOTE: writeStrict is important in order not to loose packets |
|
243 |
emotion_port.writeStrict(); |
|
251 | 244 |
|
252 | 245 |
/* |
253 | 246 |
//store joint values which we do not handle on icub here: |
examples/yarp_icub/src/icub_jointinterface.cpp | ||
---|---|---|
321 | 321 |
for (int i = ICUB_ID_NECK_TILT; i <= ICUB_ID_EYES_VERGENCE; i++) { |
322 | 322 |
set_target_in_velocitymode(i); |
323 | 323 |
} |
324 |
/* |
|
324 |
|
|
325 | 325 |
// eyelids: unfortuantely the icub has only 1dof for eyelids |
326 | 326 |
// therefore we can only use an opening value |
327 | 327 |
float opening_left = target_angle_[ICUB_ID_EYES_LEFT_LID_UPPER] |
... | ... | |
338 | 338 |
|
339 | 339 |
//mouth |
340 | 340 |
face_interface_->set_mouth(target_angle_); |
341 |
*/ |
|
342 | 341 |
|
343 | 342 |
// store joint values which we do not handle on icub here: |
344 | 343 |
double timestamp = humotion::Timestamp::now().to_seconds(); |
... | ... | |
420 | 419 |
double min, max; |
421 | 420 |
int humotion_id = convert_icub_jointid_to_humotion(icub_id); |
422 | 421 |
|
423 |
ilimits->getLimits(icub_id, &min, &max); |
|
422 |
if (!ilimits->getLimits(icub_id, &min, &max)) { |
|
423 |
cerr << "ERROR: failed to call getLimits for icub joint " << icub_id << "\n"; |
|
424 |
exit(EXIT_FAILURE); |
|
425 |
} |
|
426 |
|
|
424 | 427 |
joint_min[humotion_id] = min; |
425 | 428 |
joint_max[humotion_id] = max; |
426 | 429 |
} |
include/humotion/client/client.h | ||
---|---|---|
25 | 25 |
* Excellence Initiative. |
26 | 26 |
*/ |
27 | 27 |
|
28 |
#pragma once
|
|
29 |
#include "middleware.h"
|
|
30 |
#include <cstdio> |
|
28 |
#ifndef INCLUDE_HUMOTION_CLIENT_CLIENT_H_
|
|
29 |
#define INCLUDE_HUMOTION_CLIENT_CLIENT_H_
|
|
30 |
|
|
31 | 31 |
#include <cstdint> |
32 |
#include <cstdio> |
|
32 | 33 |
#include <string> |
33 | 34 |
|
34 |
namespace humotion{ |
|
35 |
namespace client{ |
|
35 |
#include "humotion/client/middleware.h" |
|
36 | 36 |
|
37 |
class Client{ |
|
38 |
public: |
|
37 |
namespace humotion { |
|
38 |
namespace client { |
|
39 |
|
|
40 |
class Client { |
|
41 |
public: |
|
39 | 42 |
Client(std::string name, std::string mw); |
40 |
~Client();
|
|
43 |
~Client();
|
|
41 | 44 |
|
42 | 45 |
bool ok(); |
43 | 46 |
void tick(); |
44 | 47 |
|
45 |
void update_mouth_target(MouthState s, bool send=false);
|
|
46 |
void update_gaze_target(GazeState s, bool send=false);
|
|
48 |
void update_mouth_target(MouthState s, bool send = false);
|
|
49 |
void update_gaze_target(GazeState s, bool send = false);
|
|
47 | 50 |
|
48 | 51 |
void send_all(); |
49 | 52 |
|
50 | 53 |
|
51 |
private: |
|
54 |
private:
|
|
52 | 55 |
Middleware *middleware; |
53 | 56 |
}; |
54 | 57 |
|
55 |
} |
|
56 |
} |
|
58 |
} // namespace client |
|
59 |
} // namespace humotion |
|
60 |
|
|
61 |
#endif // INCLUDE_HUMOTION_CLIENT_CLIENT_H_ |
include/humotion/client/middleware.h | ||
---|---|---|
25 | 25 |
* Excellence Initiative. |
26 | 26 |
*/ |
27 | 27 |
|
28 |
#pragma once |
|
29 |
#include <cstdio> |
|
28 |
#ifndef INCLUDE_HUMOTION_CLIENT_MIDDLEWARE_H_ |
|
29 |
#define INCLUDE_HUMOTION_CLIENT_MIDDLEWARE_H_ |
|
30 |
|
|
30 | 31 |
#include <cstdint> |
32 |
#include <cstdio> |
|
31 | 33 |
#include <string> |
32 |
#include "../mouth_state.h" |
|
33 |
#include "../gaze_state.h" |
|
34 | 34 |
|
35 |
namespace humotion{
|
|
36 |
namespace client{
|
|
35 |
#include "humotion/gaze_state.h"
|
|
36 |
#include "humotion/mouth_state.h"
|
|
37 | 37 |
|
38 |
namespace humotion { |
|
39 |
namespace client { |
|
38 | 40 |
|
39 |
class Middleware{ |
|
40 |
public: |
|
41 |
Middleware(std::string name); |
|
41 |
class Middleware {
|
|
42 |
public:
|
|
43 |
explicit Middleware(std::string name);
|
|
42 | 44 |
~Middleware(); |
43 | 45 |
|
44 | 46 |
void update_mouth_target(MouthState s, bool send); |
... | ... | |
50 | 52 |
virtual bool ok() = 0; |
51 | 53 |
virtual void tick() = 0; |
52 | 54 |
|
53 |
protected: |
|
54 |
MouthState mouth_state;
|
|
55 |
protected:
|
|
56 |
MouthState mouth_state;
|
|
55 | 57 |
GazeState gaze_state; |
56 | 58 |
std::string base_scope; |
57 | 59 |
}; |
58 | 60 |
|
59 |
} |
|
60 |
} |
|
61 |
} // namespace client |
|
62 |
} // namespace humotion |
|
63 |
|
|
64 |
#endif // INCLUDE_HUMOTION_CLIENT_MIDDLEWARE_H_ |
include/humotion/client/middleware_ros.h | ||
---|---|---|
24 | 24 |
* Forschungsgemeinschaft (DFG) in the context of the German |
25 | 25 |
* Excellence Initiative. |
26 | 26 |
*/ |
27 |
#pragma once
|
|
28 |
#include "middleware.h"
|
|
29 |
#include "ros/ros.h" |
|
27 |
#ifndef INCLUDE_HUMOTION_CLIENT_MIDDLEWARE_ROS_H_
|
|
28 |
#define INCLUDE_HUMOTION_CLIENT_MIDDLEWARE_ROS_H_
|
|
29 |
|
|
30 | 30 |
#include <boost/shared_ptr.hpp> |
31 |
#include <ros/ros.h> |
|
32 |
|
|
33 |
#include <string> |
|
34 |
|
|
35 |
#include "humotion/client/middleware.h" |
|
31 | 36 |
|
32 |
namespace humotion{ |
|
33 |
namespace client{ |
|
37 |
namespace humotion {
|
|
38 |
namespace client {
|
|
34 | 39 |
|
35 |
class MiddlewareROS : public Middleware{ |
|
36 |
public: |
|
37 |
MiddlewareROS(std::string name); |
|
40 |
class MiddlewareROS : public Middleware {
|
|
41 |
public:
|
|
42 |
explicit MiddlewareROS(std::string name);
|
|
38 | 43 |
~MiddlewareROS(); |
39 | 44 |
|
40 | 45 |
void send_mouth_target(); |
... | ... | |
42 | 47 |
bool ok(); |
43 | 48 |
void tick(); |
44 | 49 |
|
45 |
|
|
46 |
private: |
|
50 |
private: |
|
47 | 51 |
bool tick_necessary; |
48 |
//boost::shared_ptr<ros::NodeHandle> node_handle; |
|
52 |
|
|
49 | 53 |
ros::Publisher mouth_target_publisher; |
50 | 54 |
ros::Publisher gaze_target_publisher; |
51 | 55 |
}; |
52 | 56 |
|
53 |
} |
|
54 |
} |
|
57 |
} // namespace client |
|
58 |
} // namespace humotion |
|
59 |
|
|
60 |
#endif // INCLUDE_HUMOTION_CLIENT_MIDDLEWARE_ROS_H_ |
include/humotion/client/middleware_rsb.h | ||
---|---|---|
1 |
rsb support was dropped |
|
1 |
/* |
|
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 |
#ifndef INCLUDE_HUMOTION_CLIENT_MIDDLEWARE_RSB_H_ |
|
29 |
#define INCLUDE_HUMOTION_CLIENT_MIDDLEWARE_RSB_H_ |
|
30 |
// rsb support was dropped |
|
31 |
|
|
32 |
#endif // INCLUDE_HUMOTION_CLIENT_MIDDLEWARE_RSB_H_ |
include/humotion/gaze_state.h | ||
---|---|---|
25 | 25 |
* Excellence Initiative. |
26 | 26 |
*/ |
27 | 27 |
|
28 |
#pragma once |
|
28 |
#ifndef INCLUDE_HUMOTION_GAZE_STATE_H_ |
|
29 |
#define INCLUDE_HUMOTION_GAZE_STATE_H_ |
|
30 |
|
|
29 | 31 |
#include <math.h> |
30 |
#include "timestamp.h" |
|
31 | 32 |
|
32 |
namespace humotion{ |
|
33 |
class GazeState{ |
|
34 |
public: |
|
33 |
#include "humotion/timestamp.h" |
|
34 |
|
|
35 |
namespace humotion { |
|
36 |
|
|
37 |
class GazeState { |
|
38 |
public: |
|
35 | 39 |
GazeState(); |
36 | 40 |
~GazeState(); |
37 | 41 |
|
38 | 42 |
void dump(); |
39 | 43 |
|
40 |
//pan tilt roll |
|
44 |
// pan tilt roll
|
|
41 | 45 |
float pan; |
42 | 46 |
float tilt; |
43 | 47 |
float roll; |
... | ... | |
46 | 50 |
float tilt_offset; |
47 | 51 |
float roll_offset; |
48 | 52 |
|
49 |
//pan,tilt,roll can be relative or absolute |
|
53 |
// pan,tilt,roll can be relative or absolute
|
|
50 | 54 |
int gaze_type; |
51 | 55 |
|
52 |
//when was this target requested? |
|
56 |
// when was this target requested?
|
|
53 | 57 |
Timestamp timestamp; |
54 | 58 |
|
55 |
//is this relative or
|
|
59 |
// is this relative or absolute
|
|
56 | 60 |
enum GAZE_STATE_TYPE{ |
57 |
GAZETYPE_ABSOLUTE=0,
|
|
58 |
GAZETYPE_RELATIVE=1,
|
|
59 |
GAZETYPE_OVERRIDE=2
|
|
61 |
GAZETYPE_ABSOLUTE = 0,
|
|
62 |
GAZETYPE_RELATIVE = 1,
|
|
63 |
GAZETYPE_OVERRIDE = 2
|
|
60 | 64 |
}; |
61 | 65 |
|
62 |
// |
|
66 |
// eye vergence
|
|
63 | 67 |
float vergence; |
64 | 68 |
|
65 |
//eyelid opening angle |
|
69 |
// eyelid opening angle
|
|
66 | 70 |
float eyelid_opening_upper; |
67 | 71 |
float eyelid_opening_lower; |
68 | 72 |
|
69 |
//eyebrow angles |
|
73 |
// eyebrow angles
|
|
70 | 74 |
float eyebrow_left; |
71 | 75 |
float eyebrow_right; |
72 | 76 |
|
73 |
//eyeblink request |
|
77 |
// eyeblink request
|
|
74 | 78 |
int eyeblink_request_left; |
75 | 79 |
int eyeblink_request_right; |
76 |
static const int EYEBLINK_TIME_DEFAULT = 150; //ms
|
|
80 |
static const int EYEBLINK_TIME_DEFAULT = 150; // in ms
|
|
77 | 81 |
|
78 |
float distance_pt_abs(GazeState b){ |
|
82 |
float distance_pt_abs(GazeState b) {
|
|
79 | 83 |
float dist_pan = (b.pan + b.pan_offset) - (pan + pan_offset); |
80 | 84 |
float dist_tilt = (b.tilt + b.tilt_offset) - (tilt + tilt_offset); |
81 | 85 |
return sqrt(pow(dist_pan, 2.0) + pow(dist_tilt, 2.0)); |
82 | 86 |
} |
83 | 87 |
|
84 |
float distance_tilt_abs(GazeState b){ |
|
88 |
float distance_tilt_abs(GazeState b) {
|
|
85 | 89 |
float dist_tilt = (b.tilt + b.tilt_offset) - (tilt + tilt_offset); |
86 | 90 |
return fabs(dist_tilt); |
87 | 91 |
} |
88 | 92 |
|
89 |
float distance_pan_abs(GazeState b){ |
|
93 |
float distance_pan_abs(GazeState b) {
|
|
90 | 94 |
float dist_pan = (b.pan + b.pan_offset) - (pan + pan_offset); |
91 | 95 |
return fabs(dist_pan); |
92 | 96 |
} |
93 | 97 |
}; |
94 | 98 |
|
95 |
} |
|
99 |
} // namespace humotion |
|
100 |
|
|
101 |
#endif // INCLUDE_HUMOTION_GAZE_STATE_H_ |
include/humotion/mouth_state.h | ||
---|---|---|
25 | 25 |
* Excellence Initiative. |
26 | 26 |
*/ |
27 | 27 |
|
28 |
#pragma once |
|
28 |
#ifndef INCLUDE_HUMOTION_MOUTH_STATE_H_ |
|
29 |
#define INCLUDE_HUMOTION_MOUTH_STATE_H_ |
|
30 |
|
|
29 | 31 |
#include <string> |
30 | 32 |
|
31 |
namespace humotion{ |
|
32 |
class MouthState{ |
|
33 |
public: |
|
33 |
namespace humotion { |
|
34 |
|
|
35 |
class MouthState { |
|
36 |
public: |
|
34 | 37 |
MouthState(); |
35 | 38 |
~MouthState(); |
36 | 39 |
|
... | ... | |
43 | 46 |
float position_left; |
44 | 47 |
float position_center; |
45 | 48 |
float position_right; |
46 |
|
|
47 | 49 |
}; |
48 | 50 |
|
49 |
} |
|
51 |
} // namespace humotion |
|
52 |
|
|
53 |
#endif // INCLUDE_HUMOTION_MOUTH_STATE_H_ |
include/humotion/server/controller.h | ||
---|---|---|
25 | 25 |
* Excellence Initiative. |
26 | 26 |
*/ |
27 | 27 |
|
28 |
#pragma once |
|
29 |
#include "../gaze_state.h" |
|
30 |
#include "../mouth_state.h" |
|
31 |
#include "../timestamp.h" |
|
32 |
#include "motion_generator.h" |
|
33 |
#include "joint_interface.h" |
|
28 |
#ifndef INCLUDE_HUMOTION_SERVER_CONTROLLER_H_ |
|
29 |
#define INCLUDE_HUMOTION_SERVER_CONTROLLER_H_ |
|
34 | 30 |
|
35 |
namespace humotion{ |
|
36 |
namespace server{ |
|
31 |
#include <vector> |
|
37 | 32 |
|
38 |
class Controller{ |
|
39 |
public: |
|
40 |
Controller(JointInterface *j); |
|
33 |
#include "humotion/gaze_state.h" |
|
34 |
#include "humotion/mouth_state.h" |
|
35 |
#include "humotion/server/joint_interface.h" |
|
36 |
#include "humotion/server/motion_generator.h" |
|
37 |
#include "humotion/timestamp.h" |
|
38 |
|
|
39 |
namespace humotion { |
|
40 |
namespace server { |
|
41 |
|
|
42 |
class Controller { |
|
43 |
public: |
|
44 |
explicit Controller(JointInterface *j); |
|
41 | 45 |
~Controller(); |
42 | 46 |
|
43 | 47 |
void init_motion_generators(); |
44 | 48 |
void calculate_targets(); |
45 | 49 |
void publish_targets(); |
46 | 50 |
|
47 |
|
|
48 | 51 |
void set_gaze_target(GazeState s); |
49 | 52 |
void set_mouth_target(MouthState s); |
50 | 53 |
void set_activated(void); |
51 | 54 |
|
52 |
private: |
|
55 |
private:
|
|
53 | 56 |
bool activated; |
54 | 57 |
void add_motion_generator(MotionGenerator *m); |
55 | 58 |
GazeState relative_gaze_to_absolute_gaze(GazeState relative); |
... | ... | |
62 | 65 |
double last_known_absolute_target_pan; |
63 | 66 |
double last_known_absolute_target_tilt; |
64 | 67 |
double last_known_absolute_target_roll; |
65 |
|
|
66 | 68 |
}; |
67 | 69 |
|
68 |
} |
|
69 |
} |
|
70 |
} // namespace server |
|
71 |
} // namespace humotion |
|
72 |
|
|
73 |
#endif // INCLUDE_HUMOTION_SERVER_CONTROLLER_H_ |
include/humotion/server/eye_motion_generator.h | ||
---|---|---|
25 | 25 |
* Excellence Initiative. |
26 | 26 |
*/ |
27 | 27 |
|
28 |
#pragma once |
|
29 |
#include "gaze_motion_generator.h" |
|
30 |
#include "timestamped_list.h" |
|
28 |
#ifndef INCLUDE_HUMOTION_SERVER_EYE_MOTION_GENERATOR_H_ |
|
29 |
#define INCLUDE_HUMOTION_SERVER_EYE_MOTION_GENERATOR_H_ |
|
31 | 30 |
|
32 |
namespace humotion{
|
|
33 |
namespace server{
|
|
31 |
#include "humotion/server/gaze_motion_generator.h"
|
|
32 |
#include "humotion/timestamped_list.h"
|
|
34 | 33 |
|
35 |
class EyeMotionGenerator : public GazeMotionGenerator{ |
|
36 |
public: |
|
37 |
EyeMotionGenerator(JointInterface *j); |
|
34 |
namespace humotion { |
|
35 |
namespace server { |
|
36 |
|
|
37 |
class EyeMotionGenerator : public GazeMotionGenerator { |
|
38 |
public: |
|
39 |
explicit EyeMotionGenerator(JointInterface *j); |
|
38 | 40 |
~EyeMotionGenerator(); |
39 | 41 |
|
40 | 42 |
void calculate_targets(); |
... | ... | |
42 | 44 |
|
43 | 45 |
|
44 | 46 |
static const float SACCADE_SPEED_THRESHOLD; |
45 |
private: |
|
46 |
void setup_eyemotion(int dof, float target, float current_position, float current_speed, Timestamp timestamp); |
|
47 |
private: |
|
48 |
void setup_eyemotion(int dof, float target, float current_position, |
|
49 |
float current_velocity, Timestamp timestamp); |
|
47 | 50 |
|
48 | 51 |
TimestampedList tsl_gaze_target_pan; |
49 | 52 |
TimestampedList tsl_gaze_target_tilt; |
50 | 53 |
TimestampedList tsl_gaze_target_vergence; |
51 |
|
|
52 | 54 |
}; |
53 | 55 |
|
54 |
} |
|
55 |
} |
|
56 |
} // namespace server |
|
57 |
} // namespace humotion |
|
58 |
|
|
59 |
#endif // INCLUDE_HUMOTION_SERVER_EYE_MOTION_GENERATOR_H_ |
include/humotion/server/eyebrow_motion_generator.h | ||
---|---|---|
25 | 25 |
* Excellence Initiative. |
26 | 26 |
*/ |
27 | 27 |
|
28 |
#pragma once
|
|
29 |
#include "motion_generator.h"
|
|
28 |
#ifndef INCLUDE_HUMOTION_SERVER_EYEBROW_MOTION_GENERATOR_H_
|
|
29 |
#define INCLUDE_HUMOTION_SERVER_EYEBROW_MOTION_GENERATOR_H_
|
|
30 | 30 |
|
31 |
namespace humotion{ |
|
32 |
namespace server{ |
|
31 |
#include "humotion/server/motion_generator.h" |
|
33 | 32 |
|
34 |
class EyebrowMotionGenerator : public MotionGenerator{ |
|
35 |
public: |
|
36 |
EyebrowMotionGenerator(JointInterface *j); |
|
33 |
namespace humotion { |
|
34 |
namespace server { |
|
35 |
|
|
36 |
class EyebrowMotionGenerator : public MotionGenerator { |
|
37 |
public: |
|
38 |
explicit EyebrowMotionGenerator(JointInterface *j); |
|
37 | 39 |
~EyebrowMotionGenerator(); |
38 | 40 |
void calculate_targets(); |
39 | 41 |
void publish_targets(); |
40 |
private: |
|
41 | 42 |
|
43 |
private: |
|
42 | 44 |
}; |
43 | 45 |
|
44 |
} |
|
45 |
} |
|
46 |
} // namespace server |
|
47 |
} // namespace humotion |
|
48 |
|
|
49 |
#endif // INCLUDE_HUMOTION_SERVER_EYEBROW_MOTION_GENERATOR_H_ |
include/humotion/server/eyelid_motion_generator.h | ||
---|---|---|
25 | 25 |
* Excellence Initiative. |
26 | 26 |
*/ |
27 | 27 |
|
28 |
#pragma once |
|
29 |
#include "eye_motion_generator.h" |
|
30 |
#include "boost/date_time/posix_time/posix_time.hpp" |
|
28 |
#ifndef INCLUDE_HUMOTION_SERVER_EYELID_MOTION_GENERATOR_H_ |
|
29 |
#define INCLUDE_HUMOTION_SERVER_EYELID_MOTION_GENERATOR_H_ |
|
30 |
|
|
31 |
#include <boost/date_time/posix_time/posix_time.hpp> |
|
31 | 32 |
#include <boost/thread/thread_time.hpp> |
32 | 33 |
|
33 |
namespace humotion{ |
|
34 |
namespace server{ |
|
34 |
#include "humotion/server/eye_motion_generator.h" |
|
35 |
|
|
36 |
namespace humotion { |
|
37 |
namespace server { |
|
35 | 38 |
|
36 |
class EyelidMotionGenerator : public EyeMotionGenerator{ |
|
37 |
public: |
|
38 |
EyelidMotionGenerator(JointInterface *j); |
|
39 |
class EyelidMotionGenerator : public EyeMotionGenerator {
|
|
40 |
public:
|
|
41 |
explicit EyelidMotionGenerator(JointInterface *j);
|
|
39 | 42 |
~EyelidMotionGenerator(); |
40 | 43 |
|
41 | 44 |
void calculate_targets(); |
... | ... | |
43 | 46 |
|
44 | 47 |
|
45 | 48 |
|
46 |
private: |
|
49 |
private:
|
|
47 | 50 |
bool saccade_blink_active; |
48 | 51 |
bool saccade_blink_requested; |
49 | 52 |
|
50 |
enum SIDE_ID{ |
|
53 |
enum SIDE_ID {
|
|
51 | 54 |
LEFT = 0, |
52 | 55 |
RIGHT, |
53 | 56 |
SIDE_ID_SIZE |
... | ... | |
62 | 65 |
void handle_eyeblink_timeout(); |
63 | 66 |
void override_lids_for_eyeblink(); |
64 | 67 |
void check_for_saccade(); |
65 |
void start_eyeblink(int side, int duration=EYEBLINK_DURATION_MS);
|
|
68 |
void start_eyeblink(int side, int duration = EYEBLINK_DURATION_MS);
|
|
66 | 69 |
|
67 | 70 |
void close_eyelid(int joint_id); |
68 | 71 |
|
... | ... | |
75 | 78 |
boost::system_time periodic_blink_start_time; |
76 | 79 |
boost::system_time eyeblink_timeout[SIDE_ID_SIZE]; |
77 | 80 |
boost::system_time eyeblink_blocked_timeout; |
78 |
|
|
79 | 81 |
}; |
80 | 82 |
|
81 |
} |
|
82 |
} |
|
83 |
} // namespace server |
|
84 |
} // namespace humotion |
|
85 |
|
|
86 |
#endif // INCLUDE_HUMOTION_SERVER_EYELID_MOTION_GENERATOR_H_ |
include/humotion/server/gaze_motion_generator.h | ||
---|---|---|
25 | 25 |
* Excellence Initiative. |
26 | 26 |
*/ |
27 | 27 |
|
28 |
#pragma once |
|
29 |
#include "reflexxes_motion_generator.h" |
|
30 |
#include "timestamped_list.h" |
|
28 |
#ifndef INCLUDE_HUMOTION_SERVER_GAZE_MOTION_GENERATOR_H_ |
|
29 |
#define INCLUDE_HUMOTION_SERVER_GAZE_MOTION_GENERATOR_H_ |
|
31 | 30 |
|
32 |
namespace humotion{
|
|
33 |
namespace server{
|
|
31 |
#include "humotion/server/reflexxes_motion_generator.h"
|
|
32 |
#include "humotion/timestamped_list.h"
|
|
34 | 33 |
|
35 |
class GazeMotionGenerator : public ReflexxesMotionGenerator{ |
|
36 |
public: |
|
34 |
namespace humotion { |
|
35 |
namespace server { |
|
36 |
|
|
37 |
class GazeMotionGenerator : public ReflexxesMotionGenerator { |
|
38 |
public: |
|
37 | 39 |
GazeMotionGenerator(JointInterface *j, int dof, float t); |
38 | 40 |
~GazeMotionGenerator(); |
39 | 41 |
|
... | ... | |
42 | 44 |
static const float SACCADE_SPEED_THRESHOLD; |
43 | 45 |
static const float SACCADE_LATENCY; |
44 | 46 |
|
45 |
protected: |
|
47 |
protected:
|
|
46 | 48 |
GazeState get_current_gaze(); |
47 | 49 |
|
48 | 50 |
bool get_eye_saccade_active(); |
49 | 51 |
bool neck_saccade_requested; |
50 | 52 |
bool neck_saccade_omr; |
51 | 53 |
|
52 |
private: |
|
53 |
|
|
54 |
//constants |
|
54 |
private: |
|
55 |
// constants |
|
55 | 56 |
static const float NECK_SACCADE_THRESHOLD; |
56 | 57 |
static const float EYE_SACCADE_SPEED_THRESHOLD; |
57 | 58 |
static const float OMR_LIMIT_TRIGGERS_NECK_SACCADE; |
58 |
|
|
59 | 59 |
}; |
60 | 60 |
|
61 |
} |
|
62 |
} |
|
61 |
} // namespace server
|
|
62 |
} // namespace humotion
|
|
63 | 63 |
|
64 |
#endif // INCLUDE_HUMOTION_SERVER_GAZE_MOTION_GENERATOR_H_ |
include/humotion/server/joint_interface.h | ||
---|---|---|
25 | 25 |
* Excellence Initiative. |
26 | 26 |
*/ |
27 | 27 |
|
28 |
#pragma once |
|
29 |
#include <cstdio> |
|
28 |
#ifndef INCLUDE_HUMOTION_SERVER_JOINT_INTERFACE_H_ |
|
29 |
#define INCLUDE_HUMOTION_SERVER_JOINT_INTERFACE_H_ |
|
30 |
|
|
31 |
#include <boost/date_time/posix_time/posix_time.hpp> |
|
32 |
#include <boost/thread/mutex.hpp> |
|
33 |
#include <boost/thread/thread.hpp> |
|
34 |
#include <boost/thread/thread_time.hpp> |
|
35 |
|
|
30 | 36 |
#include <cstdint> |
31 |
#include <string>
|
|
37 |
#include <cstdio>
|
|
32 | 38 |
#include <map> |
33 |
#include "../timestamped_list.h" |
|
34 |
#include "../mouth_state.h" |
|
35 |
#include "../gaze_state.h" |
|
36 |
#include "boost/date_time/posix_time/posix_time.hpp" |
|
37 |
#include <boost/thread/thread_time.hpp> |
|
38 |
#include <boost/thread/thread.hpp> |
|
39 |
#include <boost/thread/mutex.hpp> |
|
39 |
#include <string> |
|
40 |
|
|
41 |
#include "humotion/gaze_state.h" |
|
42 |
#include "humotion/mouth_state.h" |
|
43 |
#include "humotion/timestamped_list.h" |
|
40 | 44 |
|
41 |
namespace humotion{ |
|
42 |
namespace server{ |
|
45 |
namespace humotion {
|
|
46 |
namespace server {
|
|
43 | 47 |
|
44 |
//forward declaration to solve include loop |
|
48 |
// forward declaration to solve include loop
|
|
45 | 49 |
class Controller; |
46 | 50 |
|
47 | 51 |
|
48 |
class JointInterface{ |
|
49 |
public: |
|
52 |
class JointInterface {
|
|
53 |
public:
|
|
50 | 54 |
JointInterface(); |
51 | 55 |
~JointInterface(); |
52 | 56 |
|
... | ... | |
80 | 84 |
|
81 | 85 |
unsigned int get_and_clear_incoming_position_count(); |
82 | 86 |
|
83 |
enum JOINT_ID_ENUM{ |
|
87 |
enum JOINT_ID_ENUM {
|
|
84 | 88 |
ZERO = 0, |
85 | 89 |
ID_LIP_LEFT_UPPER, |
86 | 90 |
ID_LIP_LEFT_LOWER, |
... | ... | |
108 | 112 |
void store_incoming_position(int joint_id, float position, Timestamp timestamp); |
109 | 113 |
void store_incoming_velocity(int joint_id, float velocity, Timestamp timestamp); |
110 | 114 |
|
111 |
protected: |
|
112 |
|
|
113 |
|
|
115 |
protected: |
|
114 | 116 |
virtual void enable_joint(int id) = 0; |
115 | 117 |
virtual void disable_joint(int id) = 0; |
116 | 118 |
float framerate; |
... | ... | |
120 | 122 |
|
121 | 123 |
|
122 | 124 |
|
123 |
private: |
|
125 |
private:
|
|
124 | 126 |
float joint_target_position_[JOINT_ID_ENUM_SIZE]; |
125 | 127 |
float joint_target_velocity_[JOINT_ID_ENUM_SIZE]; |
126 | 128 |
|
... | ... | |
132 | 134 |
bool mouth_enabled; |
133 | 135 |
bool gaze_enabled; |
134 | 136 |
unsigned int incoming_position_count; |
135 |
|
|
136 | 137 |
}; |
137 | 138 |
|
138 |
} |
|
139 |
} |
|
139 |
} // namespace server |
|
140 |
} // namespace humotion |
|
141 |
|
|
142 |
#endif // INCLUDE_HUMOTION_SERVER_JOINT_INTERFACE_H_ |
include/humotion/server/middleware.h | ||
---|---|---|
25 | 25 |
* Excellence Initiative. |
26 | 26 |
*/ |
27 | 27 |
|
28 |
#pragma once |
|
29 |
#include <cstdio> |
|
28 |
#ifndef INCLUDE_HUMOTION_SERVER_MIDDLEWARE_H_ |
|
29 |
#define INCLUDE_HUMOTION_SERVER_MIDDLEWARE_H_ |
|
30 |
|
|
30 | 31 |
#include <cstdint> |
32 |
#include <cstdio> |
|
31 | 33 |
#include <string> |
32 |
#include "../mouth_state.h" |
|
33 |
#include "../gaze_state.h" |
|
34 |
#include "controller.h" |
|
35 | 34 |
|
36 |
namespace humotion{ |
|
37 |
namespace server{ |
|
35 |
#include "humotion/gaze_state.h" |
|
36 |
#include "humotion/mouth_state.h" |
|
37 |
#include "humotion/server/controller.h" |
|
38 |
|
|
39 |
namespace humotion { |
|
40 |
namespace server { |
|
38 | 41 |
|
39 |
class Middleware{ |
|
40 |
public: |
|
42 |
class Middleware {
|
|
43 |
public:
|
|
41 | 44 |
Middleware(std::string name, Controller *c); |
42 | 45 |
~Middleware(); |
43 | 46 |
|
44 | 47 |
virtual bool ok() = 0; |
45 | 48 |
virtual void tick() = 0; |
46 | 49 |
|
47 |
protected: |
|
50 |
protected:
|
|
48 | 51 |
Controller *controller; |
49 | 52 |
std::string base_scope; |
50 |
|
|
51 |
|
|
52 | 53 |
}; |
53 | 54 |
|
54 |
} |
|
55 |
} |
|
55 |
} // namespace server |
|
56 |
} // namespace humotion |
|
57 |
|
|
58 |
#endif // INCLUDE_HUMOTION_SERVER_MIDDLEWARE_H_ |
include/humotion/server/middleware_ros.h | ||
---|---|---|
25 | 25 |
* Excellence Initiative. |
26 | 26 |
*/ |
27 | 27 |
|
28 |
#pragma once |
|
29 |
#include "middleware.h" |
|
30 |
#include "humotion/mouth.h" |
|
31 |
#include "humotion/gaze.h" |
|
32 |
#include "ros/ros.h" |
|
28 |
#ifndef INCLUDE_HUMOTION_SERVER_MIDDLEWARE_ROS_H_ |
|
29 |
#define INCLUDE_HUMOTION_SERVER_MIDDLEWARE_ROS_H_ |
|
30 |
|
|
33 | 31 |
#include <boost/shared_ptr.hpp> |
32 |
#include <ros/ros.h> |
|
33 |
#include <string> |
|
34 |
|
|
35 |
#include "humotion/gaze.h" |
|
36 |
#include "humotion/mouth.h" |
|
37 |
#include "humotion/server/middleware.h" |
|
34 | 38 |
|
35 |
namespace humotion{ |
|
36 |
namespace server{ |
|
39 |
namespace humotion {
|
|
40 |
namespace server {
|
|
37 | 41 |
|
38 |
class MiddlewareROS : public Middleware{ |
|
39 |
public: |
|
42 |
class MiddlewareROS : public Middleware {
|
|
43 |
public:
|
|
40 | 44 |
MiddlewareROS(std::string name, Controller *c); |
41 | 45 |
~MiddlewareROS(); |
42 | 46 |
bool ok(); |
43 | 47 |
void tick(); |
44 | 48 |
|
45 |
private: |
|
49 |
private:
|
|
46 | 50 |
bool tick_necessary; |
47 | 51 |
void incoming_mouth_target(const humotion::mouth::ConstPtr& msg); |
48 | 52 |
void incoming_gaze_target(const humotion::gaze::ConstPtr& msg); |
... | ... | |
51 | 55 |
ros::Subscriber gaze_target_subscriber; |
52 | 56 |
}; |
53 | 57 |
|
54 |
} |
|
55 |
} |
|
58 |
} // namespace server
|
|
59 |
} // namespace humotion
|
|
56 | 60 |
|
61 |
#endif // INCLUDE_HUMOTION_SERVER_MIDDLEWARE_ROS_H_ |
include/humotion/server/middleware_rsb.h | ||
---|---|---|
1 |
dropped RSB support |
|
1 |
/* |
|
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 |
#ifndef INCLUDE_HUMOTION_SERVER_MIDDLEWARE_RSB_H_ |
|
29 |
#define INCLUDE_HUMOTION_SERVER_MIDDLEWARE_RSB_H_ |
|
30 |
// rsb support was dropped |
|
31 |
|
|
32 |
#endif // INCLUDE_HUMOTION_SERVER_MIDDLEWARE_RSB_H_ |
include/humotion/server/motion_generator.h | ||
---|---|---|
25 | 25 |
* Excellence Initiative. |
26 | 26 |
*/ |
27 | 27 |
|
28 |
#pragma once |
|
29 |
#include "joint_interface.h" |
|
30 |
#include "boost/date_time/posix_time/posix_time.hpp" |
|
28 |
#ifndef INCLUDE_HUMOTION_SERVER_MOTION_GENERATOR_H_ |
|
29 |
#define INCLUDE_HUMOTION_SERVER_MOTION_GENERATOR_H_ |
|
30 |
|
|
31 |
#include <boost/date_time/posix_time/posix_time.hpp> |
|
32 |
|
|
31 | 33 |
#include <string> |
32 | 34 |
|
33 |
namespace humotion{ |
|
34 |
namespace server{ |
|
35 |
#include "humotion/server/joint_interface.h" |
|
36 |
|
|
37 |
namespace humotion { |
|
38 |
namespace server { |
|
35 | 39 |
|
36 |
class MotionGenerator{ |
|
37 |
public: |
|
38 |
MotionGenerator(JointInterface *j); |
|
40 |
class MotionGenerator {
|
|
41 |
public:
|
|
42 |
explicit MotionGenerator(JointInterface *j);
|
|
39 | 43 |
~MotionGenerator(); |
40 | 44 |
|
41 |
virtual void calculate_targets()=0;
|
|
42 |
virtual void publish_targets()=0;
|
|
45 |
virtual void calculate_targets() = 0;
|
|
46 |
virtual void publish_targets() = 0;
|
|
43 | 47 |
|
44 | 48 |
virtual void set_gaze_target(GazeState s); |
45 | 49 |
virtual void set_mouth_target(MouthState s); |
46 | 50 |
|
47 |
protected: |
|
51 |
protected:
|
|
48 | 52 |
float get_current_position(int joint_id); |
49 | 53 |
float get_current_speed(int joint_id); |
50 | 54 |
humotion::Timestamp get_timestamped_state(int joint_id, float *position, float *velocity); |
... | ... | |
52 | 56 |
|
53 | 57 |
JointInterface *joint_interface; |
54 | 58 |
|
55 |
//GAZE:
|
|
59 |
// gaze
|
|
56 | 60 |
GazeState requested_gaze_state; |
57 | 61 |
boost::system_time last_gaze_target_update; |
58 | 62 |
bool gaze_target_input_active(); |
59 | 63 |
|
60 |
//MOUTH
|
|
64 |
// mouth
|
|
61 | 65 |
MouthState requested_mouth_target; |
62 | 66 |
boost::system_time last_mouth_target_update; |
63 | 67 |
bool mouth_target_input_active(); |
64 |
|
|
65 | 68 |
}; |
66 | 69 |
|
67 |
} |
|
68 |
} |
|
70 |
} // namespace server |
|
71 |
} // namespace humotion |
|
72 |
|
|
73 |
#endif // INCLUDE_HUMOTION_SERVER_MOTION_GENERATOR_H_ |
include/humotion/server/mouth_motion_generator.h | ||
---|---|---|
25 | 25 |
* Excellence Initiative. |
26 | 26 |
*/ |
27 | 27 |
|
28 |
#pragma once
|
|
29 |
#include "motion_generator.h"
|
|
28 |
#ifndef INCLUDE_HUMOTION_SERVER_MOUTH_MOTION_GENERATOR_H_
|
|
29 |
#define INCLUDE_HUMOTION_SERVER_MOUTH_MOTION_GENERATOR_H_
|
|
30 | 30 |
|
31 |
namespace humotion{ |
|
32 |
namespace server{ |
|
31 |
#include "humotion/server/motion_generator.h" |
|
33 | 32 |
|
34 |
class MouthMotionGenerator : public MotionGenerator{ |
|
35 |
public: |
|
36 |
MouthMotionGenerator(JointInterface *j); |
|
33 |
namespace humotion { |
|
34 |
namespace server { |
|
35 |
|
|
36 |
class MouthMotionGenerator : public MotionGenerator { |
|
37 |
public: |
|
38 |
explicit MouthMotionGenerator(JointInterface *j); |
|
37 | 39 |
~MouthMotionGenerator(); |
38 | 40 |
void calculate_targets(); |
39 | 41 |
void publish_targets(); |
40 | 42 |
|
41 |
private: |
|
43 |
private:
|
|
42 | 44 |
void calculate_mouth_target(int upper, int lower); |
43 | 45 |
float mouthstate_to_opening(MouthState m, int e); |
44 | 46 |
float mouthstate_to_position(MouthState m, int e); |
45 | 47 |
void update_mouth_target(int upper_id, int lower_id); |
46 | 48 |
|
47 |
//minimum mouth opening:
|
|
49 |
// minimum mouth opening
|
|
48 | 50 |
static const float MOUTH_MIN_OPENING; |
49 | 51 |
}; |
50 | 52 |
|
51 |
} |
|
52 |
} |
|
53 |
} // namespace server |
|
54 |
} // namespace humotion |
|
55 |
|
|
56 |
#endif // INCLUDE_HUMOTION_SERVER_MOUTH_MOTION_GENERATOR_H_ |
include/humotion/server/neck_motion_generator.h | ||
---|---|---|
25 | 25 |
* Excellence Initiative. |
26 | 26 |
*/ |
27 | 27 |
|
28 |
#pragma once |
|
29 |
#include "gaze_motion_generator.h" |
|
28 |
#ifndef INCLUDE_HUMOTION_SERVER_NECK_MOTION_GENERATOR_H_ |
|
29 |
#define INCLUDE_HUMOTION_SERVER_NECK_MOTION_GENERATOR_H_ |
|
30 |
#include "humotion/server/gaze_motion_generator.h" |
|
30 | 31 |
|
31 |
namespace humotion{ |
|
32 |
namespace server{ |
|
32 |
namespace humotion {
|
|
33 |
namespace server {
|
|
33 | 34 |
|
34 | 35 |
class NeckMotionGenerator : public GazeMotionGenerator { |
35 |
public: |
|
36 |
NeckMotionGenerator(JointInterface *j); |
|
36 |
public:
|
|
37 |
explicit NeckMotionGenerator(JointInterface *j);
|
|
37 | 38 |
~NeckMotionGenerator(); |
38 | 39 |
void calculate_targets(); |
39 | 40 |
void publish_targets(); |
40 |
void setup_neckmotion(int dof, float target, float current_position, float current_speed, Timestamp timestamp); |
|
41 |
void setup_neckmotion(int dof, float target, float current_position, |
|
42 |
float current_velocity, Timestamp timestamp); |
|
41 | 43 |
|
42 |
private: |
|
44 |
private:
|
|
43 | 45 |
float get_breath_offset(); |
44 | 46 |
|
45 | 47 |
GazeState previous_neck_target; |
... | ... | |
53 | 55 |
float breath_time; |
54 | 56 |
static const float CONST_BREATH_PERIOD; |
55 | 57 |
static const float CONST_BREATH_AMPLITUDE; |
56 |
|
|
57 |
|
|
58 | 58 |
}; |
59 | 59 |
|
60 |
} |
|
61 |
} |
|
60 |
} // namespace server |
|
61 |
} // namespace humotion |
|
62 |
|
|
63 |
#endif // INCLUDE_HUMOTION_SERVER_NECK_MOTION_GENERATOR_H_ |
include/humotion/server/reflexxes_motion_generator.h | ||
---|---|---|
25 | 25 |
* Excellence Initiative. |
26 | 26 |
*/ |
27 | 27 |
|
28 |
#pragma once |
|
29 |
#include "motion_generator.h" |
|
28 |
#ifndef INCLUDE_HUMOTION_SERVER_REFLEXXES_MOTION_GENERATOR_H_ |
|
29 |
#define INCLUDE_HUMOTION_SERVER_REFLEXXES_MOTION_GENERATOR_H_ |
|
30 |
|
|
30 | 31 |
#include <ReflexxesAPI.h> |
31 | 32 |
#include <RMLPositionFlags.h> |
32 | 33 |
#include <RMLPositionInputParameters.h> |
33 | 34 |
#include <RMLPositionOutputParameters.h> |
34 | 35 |
|
35 |
namespace humotion{ |
|
36 |
namespace server{ |
|
36 |
#include "humotion/server/motion_generator.h" |
|
37 |
|
|
38 |
namespace humotion { |
|
39 |
namespace server { |
|
37 | 40 |
|
38 | 41 |
class ReflexxesMotionGenerator : public MotionGenerator{ |
39 |
public: |
|
42 |
public:
|
|
40 | 43 |
ReflexxesMotionGenerator(JointInterface *j, int dof, float t); |
41 | 44 |
~ReflexxesMotionGenerator(); |
42 | 45 |
|
43 |
protected: |
|
44 |
void reflexxes_set_input(int dof, float target, float current_position, float current_speed, Timestamp timestamp, float max_speed, float max_accel); |
|
46 |
protected: |
|
47 |
void reflexxes_set_input(int dof, float target, |
|
48 |
float current_position, float current_velocity, |
|
49 |
Timestamp timestamp, float max_speed, float max_accel); |
|
45 | 50 |
void reflexxes_calculate_profile(); |
46 | 51 |
|
47 | 52 |
//***************************************** |
... | ... | |
52 | 57 |
//***************************************** |
53 | 58 |
int dof_count; |
54 | 59 |
|
55 |
private: |
|
56 |
|
|
60 |
private: |
|
57 | 61 |
}; |
58 | 62 |
|
59 |
} |
|
60 |
} |
|
63 |
} // namespace server |
|
64 |
} // namespace humotion |
|
65 |
|
|
66 |
#endif // INCLUDE_HUMOTION_SERVER_REFLEXXES_MOTION_GENERATOR_H_ |
include/humotion/server/server.h | ||
---|---|---|
25 | 25 |
* Excellence Initiative. |
26 | 26 |
*/ |
27 | 27 |
|
28 |
#pragma once |
|
28 |
#ifndef INCLUDE_HUMOTION_SERVER_SERVER_H_ |
|
29 |
#define INCLUDE_HUMOTION_SERVER_SERVER_H_ |
|
30 |
|
|
31 |
#include <boost/thread/thread.hpp> |
|
32 |
#include <ros/ros.h> |
|
29 | 33 |
|
30 |
#include "ros/ros.h" |
|
31 |
#include "middleware.h" |
|
32 |
#include "controller.h" |
|
33 |
#include <cstdio> |
|
34 | 34 |
#include <cstdint> |
35 |
#include <cstdio> |
|
35 | 36 |
#include <string> |
36 |
#include <boost/thread/thread.hpp> |
|
37 | 37 |
|
38 |
namespace humotion{ |
|
39 |
namespace server{ |
|
38 |
#include "humotion/server/controller.h" |
|
39 |
#include "humotion/server/middleware.h" |
|
40 |
|
|
41 |
namespace humotion { |
|
42 |
namespace server { |
|
40 | 43 |
|
41 |
class Server{ |
|
42 |
public: |
|
44 |
class Server {
|
|
45 |
public:
|
|
43 | 46 |
Server(std::string name, std::string mw, JointInterface *_joint_interface); |
44 |
~Server();
|
|
47 |
~Server();
|
|
45 | 48 |
bool ok(); |
46 | 49 |
static const float MOTION_UPDATERATE; |
47 | 50 |
|
48 |
private: |
|
51 |
private:
|
|
49 | 52 |
void start_motion_generation_thread(); |
50 | 53 |
void motion_generation_thread(); |
51 | 54 |
boost::thread *motion_generation_thread_ptr; |
... | ... | |
55 | 58 |
JointInterface *joint_interface; |
56 | 59 |
}; |
57 | 60 |
|
58 |
} |
|
59 |
} |
|
61 |
} // namespace server |
|
62 |
} // namespace humotion |
|
63 |
|
|
64 |
#endif // INCLUDE_HUMOTION_SERVER_SERVER_H_ |
include/humotion/timestamp.h | ||
---|---|---|
25 | 25 |
* Excellence Initiative. |
26 | 26 |
*/ |
27 | 27 |
|
28 |
#pragma once |
|
29 |
#include <stdlib.h> |
|
28 |
#ifndef INCLUDE_HUMOTION_TIMESTAMP_H_ |
|
29 |
#define INCLUDE_HUMOTION_TIMESTAMP_H_ |
|
30 |
|
|
30 | 31 |
#include <stdio.h> |
32 |
#include <stdlib.h> |
|
31 | 33 |
#include <unistd.h> |
34 |
|
|
32 | 35 |
#include <string> |
33 | 36 |
|
34 |
namespace humotion{ |
|
37 |
namespace humotion {
|
|
35 | 38 |
|
36 |
class Timestamp{ |
|
37 |
public: |
|
39 |
class Timestamp {
|
|
40 |
public:
|
|
38 | 41 |
Timestamp(void); |
39 | 42 |
Timestamp(uint32_t _sec, uint32_t _nsec); |
40 |
Timestamp(double dsec); |
|
43 |
explicit Timestamp(double dsec);
|
|
41 | 44 |
|
42 | 45 |
void set(uint32_t _sec, uint32_t _nsec); |
43 | 46 |
void set(Timestamp a); |
44 | 47 |
|
45 | 48 |
static Timestamp now(void); |
46 | 49 |
|
47 |
|
|
48 | 50 |
bool is_null(void); |
49 | 51 |
double to_seconds(void); |
50 | 52 |
|
51 |
bool operator> (Timestamp &cmp);
|
|
52 |
bool operator<= (Timestamp &cmp);
|
|
53 |
bool operator< (Timestamp &cmp);
|
|
54 |
bool operator>= (Timestamp &cmp);
|
|
55 |
bool operator== (Timestamp &cmp);
|
|
56 |
bool operator!= (Timestamp &cmp);
|
|
53 |
bool operator> (const Timestamp &cmp) const;
|
|
54 |
bool operator<= (const Timestamp &cmp) const;
|
|
55 |
bool operator< (const Timestamp &cmp) const;
|
|
56 |
bool operator>= (const Timestamp &cmp) const;
|
|
57 |
bool operator== (const Timestamp &cmp) const;
|
|
58 |
bool operator!= (const Timestamp &cmp) const;
|
|
57 | 59 |
|
58 | 60 |
uint32_t sec; |
59 | 61 |
uint32_t nsec; |
60 |
|
|
61 | 62 |
}; |
62 | 63 |
|
64 |
} // namespace humotion |
|
63 | 65 |
|
64 |
} |
|
66 |
#endif // INCLUDE_HUMOTION_TIMESTAMP_H_ |
include/humotion/timestamped_float.h | ||
---|---|---|
25 | 25 |
* Excellence Initiative. |
26 | 26 |
*/ |
27 | 27 |
|
28 |
#pragma once |
|
29 |
#include <stdlib.h> |
|
28 |
#ifndef INCLUDE_HUMOTION_TIMESTAMPED_FLOAT_H_ |
|
29 |
#define INCLUDE_HUMOTION_TIMESTAMPED_FLOAT_H_ |
|
30 |
|
|
30 | 31 |
#include <stdio.h> |
Also available in: Unified diff