hlrc / server / include / ROS / LookatCallbackWrapperROS.h @ 2cf3c285
History | View | Annotate | Download (4.337 KB)
1 |
/*
|
---|---|
2 |
* This file is part of hlrc_server
|
3 |
*
|
4 |
* Copyright(c) sschulz <AT> techfak.uni-bielefeld.de
|
5 |
* http://opensource.cit-ec.de/projects/hlrc_server
|
6 |
*
|
7 |
* This file may be licensed under the terms of the
|
8 |
* GNU General Public License Version 3 (the ``GPL''),
|
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 GPL for the specific language
|
14 |
* governing rights and limitations.
|
15 |
*
|
16 |
* You should have received a copy of the GPL along with this
|
17 |
* program. If not, go to http://www.gnu.org/licenses/gpl.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 |
|
29 |
#pragma once
|
30 |
#include "hlrc_server/lookattargetAction.h" |
31 |
#include "CallbackWrapperROS.h" |
32 |
#include <tf2_ros/buffer.h> |
33 |
#include <tf2_eigen/tf2_eigen.h> |
34 |
#include <angles/angles.h> |
35 |
|
36 |
//callback handler incoming lookat requests:
|
37 |
class LookatCallbackWrapper : CallbackWrapper<hlrc_server::lookattargetAction>{ |
38 |
protected:
|
39 |
hlrc_server::lookattargetFeedback feedback; |
40 |
hlrc_server::lookattargetResult result; |
41 |
const tf2_ros::Buffer& tfBuffer;
|
42 |
const std::string FLOBI_BASE_LINK="BASE_LINK"; |
43 |
Eigen::Affine3d eig_base_to_eyes; // base to center of eyes
|
44 |
double eye_distance; // distance from center of eyes to eye frame |
45 |
|
46 |
public:
|
47 |
|
48 |
LookatCallbackWrapper(Middleware *mw, std::string scope, std::string name, const tf2_ros::Buffer &tfBuffer)
|
49 |
: CallbackWrapper<hlrc_server::lookattargetAction>(mw, scope, name, boost::bind(&LookatCallbackWrapper::call, this, _1)) |
50 |
, tfBuffer(tfBuffer) |
51 |
{ |
52 |
eye_distance = 0.15 / 2; |
53 |
} |
54 |
|
55 |
void call(const GoalConstPtr &goal){ |
56 |
feedback.result = 1;
|
57 |
|
58 |
hlrc_server::lookattargetGoalConstPtr request = goal; |
59 |
const geometry_msgs::Point &p = request->point;
|
60 |
|
61 |
Eigen::Vector3d target(p.x, p.y, p.z); |
62 |
try { |
63 |
if (!request->header.frame_id.empty()) { // only consider tf, when frame_id is non-empty |
64 |
geometry_msgs::TransformStamped source_to_base = |
65 |
// lookupTransform can throw
|
66 |
tfBuffer.lookupTransform(FLOBI_BASE_LINK, request->header.frame_id, |
67 |
request->header.stamp, ros::Duration(0.01)); |
68 |
|
69 |
Eigen::Affine3d eig_source_to_eyes; |
70 |
eig_source_to_eyes = tf2::transformToEigen(source_to_base) * eig_base_to_eyes; |
71 |
target = eig_source_to_eyes * target; |
72 |
} else {
|
73 |
// otherwise we interpret target directly w.r.t. eye center
|
74 |
} |
75 |
} catch (const std::exception &e) {
|
76 |
// Failed to resolve tf?
|
77 |
result.result = 0;
|
78 |
as_.setAborted(result, e.what()); |
79 |
return;
|
80 |
} |
81 |
|
82 |
// compute pan + tilt: let point z-axis of eyes frames towards target
|
83 |
humotion::GazeState gaze_state; |
84 |
double distance = target.norm();
|
85 |
if (distance > 1e-3) { |
86 |
target /= distance; |
87 |
|
88 |
// pan = rotation about x-axis: angle of projection of target onto yz-plane to z-axis
|
89 |
gaze_state.pan = 90-angles::to_degrees(atan2(target.z(), target.y()));
|
90 |
// tilt = rotation about y-axis: angle between target and yz-plane
|
91 |
Eigen::Vector2d projection(target.y(), target.z()); |
92 |
gaze_state.tilt = angles::to_degrees(atan2(target.x(), projection.norm())); |
93 |
} |
94 |
// fill in rest of gaze_state
|
95 |
gaze_state.roll = request->roll; |
96 |
gaze_state.vergence = angles::to_degrees(atan2(eye_distance, distance)); |
97 |
|
98 |
// use timestamp from request
|
99 |
gaze_state.timestamp.set(request->header.stamp.sec, request->header.stamp.nsec); |
100 |
gaze_state.gaze_type = humotion::GazeState::GAZETYPE_ABSOLUTE; |
101 |
|
102 |
// processing
|
103 |
as_.publishFeedback(feedback); |
104 |
|
105 |
// send to application:
|
106 |
mw->gaze_callback(gaze_state); |
107 |
|
108 |
if (feedback.result){
|
109 |
result.result = feedback.result; |
110 |
as_.setSucceeded(result); |
111 |
}else{
|
112 |
as_.setAborted(result); |
113 |
} |
114 |
|
115 |
} |
116 |
}; |