Statistics
| Branch: | Tag: | Revision:

humotion / src / server / middleware_ros.cpp @ 277050c7

History | View | Annotate | Download (7.246 KB)

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
#include <boost/algorithm/string/classification.hpp>
29

    
30
#include <string>
31

    
32
#include "humotion/server/middleware_ros.h"
33

    
34
using humotion::server::MiddlewareROS;
35

    
36
//! constructor
37
MiddlewareROS::MiddlewareROS(std::string scope, Controller *c)
38
    : Middleware(scope, c) {
39
    ROS_DEBUG_STREAM_NAMED("MiddlewareROS", "will use ros middleware");
40

    
41
    // start ros core?
42
    if (ros::isInitialized()) {
43
        // oh another process is doing ros comm, fine, we do not need to call it
44
        tick_necessary_ = false;
45
    } else {
46
        // we have to take care of ros
47
        ROS_DEBUG_STREAM_NAMED("MiddlewareROS", "no active ros middleware, will call ros::init() "
48
               "now and we will call tick() periodically!\n");
49

    
50
        std::string node_name = "humotion_server__"+ scope;
51
        node_name.erase(std::remove(node_name.begin(), node_name.end(), '/'), node_name.end());
52

    
53
        ROS_DEBUG_STREAM_NAMED("MiddlewareROS", "registering on ROS as node " << node_name.c_str());
54

    
55
        ros::M_string no_remapping;
56
        ros::init(no_remapping, node_name);
57
        tick_necessary_ = true;
58
    }
59

    
60
    // create node handle
61
    ros::NodeHandle n;
62
    ros::NodeHandle pnh("~");
63

    
64
    // set up subscribers
65
    mouth_target_subscriber_ = n.subscribe(scope + "/humotion/mouth/target", 150,
66
                                          &MiddlewareROS::incoming_mouth_target ,
67
                                          this, ros::TransportHints().unreliable());
68
    gaze_target_subscriber_  = n.subscribe(scope + "/humotion/gaze/target",  150,
69
                                          &MiddlewareROS::incoming_gaze_target,
70
                                          this, ros::TransportHints().unreliable());
71

    
72
    // set up dynamic reconfiguration service
73
    attach_to_reconfiguration_server(pnh);
74
}
75

    
76
//! callback for incoming dynamic reconfigure requests:
77
void MiddlewareROS::dynamic_reconfigure_callback(const humotion::humotionConfig &dyn_config,
78
                                                  uint32_t level) {
79
    // fetch config
80
    humotion::server::Config *config = controller_->get_config();
81

    
82
    // saccade detection thresholds
83
    config->threshold_velocity_eye_saccade = dyn_config.threshold_velocity_eye_saccade;
84
    config->threshold_angle_neck_saccade = dyn_config.threshold_angle_neck_saccade;
85
    config->threshold_angle_omr_limit = dyn_config.threshold_angle_omr_limit;
86

    
87

    
88
    // neck motion generation configuration
89
    config->scale_velocity_neck = dyn_config.scale_velocity_neck;
90
    config->scale_acceleration_neck = dyn_config.scale_acceleration_neck;
91
    config->limit_velocity_neck = dyn_config.limit_velocity_neck;
92
    config->limit_acceleration_neck = dyn_config.limit_acceleration_neck;
93

    
94
    // eye motion generation configuration
95
    config->scale_velocity_eye = dyn_config.scale_velocity_eye;
96
    config->scale_acceleration_eye = dyn_config.scale_acceleration_eye;
97
    config->limit_velocity_eye = dyn_config.limit_velocity_eye;
98
    config->limit_acceleration_eye = dyn_config.limit_acceleration_eye;
99

    
100
    // parameters fo the breathing pattern
101
    config->breath_period = dyn_config.breath_period;
102
    config->breath_amplitude = dyn_config.breath_amplitude;
103

    
104
    // parameters for eye blinking
105
    config->eyeblink_duration = dyn_config.eyeblink_duration;
106
    config->eyeblink_periodic_distribution_lower = dyn_config.eyeblink_periodic_distribution_lower;
107
    config->eyeblink_periodic_distribution_upper = dyn_config.eyeblink_periodic_distribution_upper;
108
    config->eyeblink_probability_after_saccade = dyn_config.eyeblink_probability_after_saccade;
109
    config->eyeblink_blocked_time = dyn_config.eyeblink_blocked_time;
110
}
111

    
112
//! attach to dynamic reconfigure server
113
void MiddlewareROS::attach_to_reconfiguration_server(ros::NodeHandle priv_nodehandle) {
114
    ROS_DEBUG_STREAM_NAMED("MiddlewareROS", "connecting to dynamic reconfiguration server");
115

    
116
    ros::NodeHandle reconf_node(priv_nodehandle, "humotion/configuration");
117

    
118
    reconf_server_ = new dynamic_reconfigure::Server<humotion::humotionConfig>(reconf_node);
119
    reconf_server_->setCallback(boost::bind(
120
                                    &MiddlewareROS::dynamic_reconfigure_callback, this, _1, _2));
121
}
122

    
123
//! destructor
124
MiddlewareROS::~MiddlewareROS() {
125
}
126

    
127
//! connection ok?
128
//! \return true if conn is alive
129
bool MiddlewareROS::ok() {
130
    return ros::ok();
131
}
132

    
133
//! do a single tick
134
void MiddlewareROS::tick() {
135
    if (tick_necessary_) {
136
        ros::spinOnce();
137
    }
138
}
139

    
140
//! callback to handle incoming mouth  target
141
void MiddlewareROS::incoming_mouth_target(const humotion::mouth::ConstPtr& msg) {
142
    // printf("> incoming mouth_target\n");
143
    MouthState mouth_state;
144

    
145
    mouth_state.position_left   = msg->position.left;
146
    mouth_state.position_center = msg->position.center;
147
    mouth_state.position_right  = msg->position.right;
148

    
149
    mouth_state.opening_left   = msg->opening.left;
150
    mouth_state.opening_center = msg->opening.center;
151
    mouth_state.opening_right  = msg->opening.right;
152

    
153
    controller_->set_mouth_target(mouth_state);
154
}
155

    
156

    
157
//! callback to handle incoming gaze  target
158
void MiddlewareROS::incoming_gaze_target(const humotion::gaze::ConstPtr& msg) {
159
    GazeState gaze_state;
160
    // printf("> incoming gaze_target [P:%3.1f, T:%3.1f, R:%3.1f] %d = %s\n",
161
    //          msg->pan, msg->tilt, msg->roll, msg->type,
162
    //          msg->type==humotion::gaze::GAZETYPE_ABSOLUTE?"ABSOLUTE":"RELATIVE");
163

    
164
    gaze_state.pan  = msg->pan;
165
    gaze_state.tilt = msg->tilt;
166
    gaze_state.roll = msg->roll;
167
    gaze_state.vergence = msg->vergence;
168

    
169
    gaze_state.pan_offset  = msg->pan_offset;
170
    gaze_state.tilt_offset = msg->tilt_offset;
171
    gaze_state.roll_offset = msg->roll_offset;
172

    
173
    gaze_state.eyelid_opening_upper = msg->eyelid_opening_upper;
174
    gaze_state.eyelid_opening_lower = msg->eyelid_opening_lower;
175

    
176
    gaze_state.eyebrow_left = msg->eyebrow_left;
177
    gaze_state.eyebrow_right = msg->eyebrow_right;
178

    
179
    gaze_state.eyeblink_request_left = msg->eyeblink_request_left;
180
    gaze_state.eyeblink_request_right = msg->eyeblink_request_right;
181

    
182
    if (msg->gaze_type == humotion::gaze::GAZETYPE_ABSOLUTE) {
183
        gaze_state.gaze_type = GazeState::GAZETYPE_ABSOLUTE;
184
    } else {
185
        gaze_state.gaze_type = GazeState::GAZETYPE_RELATIVE;
186
    }
187

    
188
    gaze_state.timestamp.set(msg->gaze_timestamp.sec, msg->gaze_timestamp.nsec);
189

    
190
    controller_->set_gaze_target(gaze_state);
191
}
192