humotion / src / server / middleware_ros.cpp @ 414a3516
History | View | Annotate | Download (4.521 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 | #include "server/middleware_ros.h" |
||
29 | |||
30 | #include <boost/range/algorithm/remove_if.hpp> |
||
31 | #include <boost/algorithm/string/classification.hpp> |
||
32 | using namespace std; |
||
33 | using namespace boost; |
||
34 | using namespace humotion; |
||
35 | using namespace humotion::server; |
||
36 | |||
37 | //! constructor
|
||
38 | 5d7ba19c | Simon Schulz | MiddlewareROS::MiddlewareROS(string scope, Controller *c)
|
39 | : Middleware(scope, c){ |
||
40 | 8c6c1163 | Simon Schulz | |
41 | 5d7ba19c | Simon Schulz | printf("> using ROS middleware\n");
|
42 | 8c6c1163 | Simon Schulz | //start ros core?
|
43 | if (ros::isInitialized()){
|
||
44 | dff8ce51 | Simon Schulz | //oh another process is doing ros comm, fine, we do not need to call it
|
45 | 8c6c1163 | Simon Schulz | tick_necessary = false;
|
46 | }else{
|
||
47 | //we have to take care of ros
|
||
48 | printf("> no active ros middleware, calling ros::init() and we will call tick() periodically!");
|
||
49 | string node_name = "humotion_server__"+ scope; |
||
50 | node_name.erase(boost::remove_if(node_name, boost::is_any_of("/")), node_name.end());
|
||
51 | printf("> registering on ROS as node %s\n",node_name.c_str());
|
||
52 | ros::M_string no_remapping; |
||
53 | ros::init(no_remapping, node_name); |
||
54 | tick_necessary = true;
|
||
55 | } |
||
56 | |||
57 | //create node handle
|
||
58 | ros::NodeHandle n; |
||
59 | |||
60 | //set up subscribers:
|
||
61 | mouth_target_subscriber = n.subscribe(scope + "/humotion/mouth/target", 150, &MiddlewareROS::incoming_mouth_target , this, ros::TransportHints().unreliable()); |
||
62 | gaze_target_subscriber = n.subscribe(scope + "/humotion/gaze/target", 150, &MiddlewareROS::incoming_gaze_target, this, ros::TransportHints().unreliable()); |
||
63 | |||
64 | } |
||
65 | |||
66 | //! destructor
|
||
67 | MiddlewareROS::~MiddlewareROS(){ |
||
68 | } |
||
69 | |||
70 | //! connection ok?
|
||
71 | //! \return true if conn is alive
|
||
72 | bool MiddlewareROS::ok(){
|
||
73 | return ros::ok();
|
||
74 | } |
||
75 | |||
76 | //! do a single tick
|
||
77 | void MiddlewareROS::tick(){
|
||
78 | if (tick_necessary){
|
||
79 | ros::spinOnce(); |
||
80 | } |
||
81 | } |
||
82 | |||
83 | //! callback to handle incoming mouth target
|
||
84 | void MiddlewareROS::incoming_mouth_target(const humotion::mouth::ConstPtr& msg){ |
||
85 | //printf("> incoming mouth_target\n");
|
||
86 | MouthState mouth_state; |
||
87 | |||
88 | mouth_state.position_left = msg->position.left; |
||
89 | mouth_state.position_center = msg->position.center; |
||
90 | mouth_state.position_right = msg->position.right; |
||
91 | |||
92 | mouth_state.opening_left = msg->opening.left; |
||
93 | mouth_state.opening_center = msg->opening.center; |
||
94 | mouth_state.opening_right = msg->opening.right; |
||
95 | |||
96 | controller->set_mouth_target(mouth_state); |
||
97 | } |
||
98 | |||
99 | |||
100 | //! callback to handle incoming gaze target
|
||
101 | void MiddlewareROS::incoming_gaze_target(const humotion::gaze::ConstPtr& msg){ |
||
102 | GazeState gaze_state; |
||
103 | 4e61b076 | Simon Schulz | //printf("> incoming gaze_target [P:%3.1f, T:%3.1f, R:%3.1f] %d = %s\n", msg->pan, msg->tilt, msg->roll, msg->type, msg->type==humotion::gaze::GAZETYPE_ABSOLUTE?"ABSOLUTE":"RELATIVE");
|
104 | 8c6c1163 | Simon Schulz | |
105 | gaze_state.pan = msg->pan; |
||
106 | gaze_state.tilt = msg->tilt; |
||
107 | gaze_state.roll = msg->roll; |
||
108 | gaze_state.vergence = msg->vergence; |
||
109 | |||
110 | gaze_state.pan_offset = msg->pan_offset; |
||
111 | gaze_state.tilt_offset = msg->tilt_offset; |
||
112 | gaze_state.roll_offset = msg->roll_offset; |
||
113 | |||
114 | gaze_state.eyelid_opening_upper = msg->eyelid_opening_upper; |
||
115 | gaze_state.eyelid_opening_lower = msg->eyelid_opening_lower; |
||
116 | |||
117 | gaze_state.eyebrow_left = msg->eyebrow_left; |
||
118 | gaze_state.eyebrow_right = msg->eyebrow_right; |
||
119 | |||
120 | gaze_state.eyeblink_request_left = msg->eyeblink_request_left; |
||
121 | gaze_state.eyeblink_request_right = msg->eyeblink_request_right; |
||
122 | |||
123 | 1c758459 | Simon Schulz | if (msg->gaze_type == humotion::gaze::GAZETYPE_ABSOLUTE){
|
124 | gaze_state.gaze_type = GazeState::GAZETYPE_ABSOLUTE; |
||
125 | }else{
|
||
126 | gaze_state.gaze_type = GazeState::GAZETYPE_RELATIVE; |
||
127 | } |
||
128 | 32327f15 | Simon Schulz | |
129 | gaze_state.timestamp.set(msg->gaze_timestamp.sec, msg->gaze_timestamp.nsec); |
||
130 | 8c6c1163 | Simon Schulz | |
131 | controller->set_gaze_target(gaze_state); |
||
132 | |||
133 | } |