hlrc / server / include / ROS / LookatCallbackWrapperROS.h @ 5c4330e9
History | View | Annotate | Download (4.899 KB)
1 | b47687f8 | Robert Haschke | /*
|
---|---|---|---|
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 | 2cf3c285 | Robert Haschke | #include <tf2_ros/buffer.h> |
33 | #include <tf2_eigen/tf2_eigen.h> |
||
34 | #include <angles/angles.h> |
||
35 | b47687f8 | Robert Haschke | |
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 | 2cf3c285 | Robert Haschke | const tf2_ros::Buffer& tfBuffer;
|
42 | const std::string FLOBI_BASE_LINK="BASE_LINK"; |
||
43 | 87c0fad1 | Robert Haschke | // pan/tilt will be computed w.r.t. to virtual frame at height of eyes
|
44 | Eigen::Affine3d eig_eyes_to_base; |
||
45 | 2cf3c285 | Robert Haschke | double eye_distance; // distance from center of eyes to eye frame |
46 | b47687f8 | Robert Haschke | |
47 | public:
|
||
48 | |||
49 | 2cf3c285 | Robert Haschke | LookatCallbackWrapper(Middleware *mw, std::string scope, std::string name, const tf2_ros::Buffer &tfBuffer)
|
50 | b47687f8 | Robert Haschke | : CallbackWrapper<hlrc_server::lookattargetAction>(mw, scope, name, boost::bind(&LookatCallbackWrapper::call, this, _1)) |
51 | 2cf3c285 | Robert Haschke | , tfBuffer(tfBuffer) |
52 | b47687f8 | Robert Haschke | { |
53 | 87c0fad1 | Robert Haschke | // eyes frame has z-axis pointing along view dir (90° rotation w.r.t. base)
|
54 | // and z-position is shifted to height of eyes
|
||
55 | eig_eyes_to_base = (Eigen::Translation3d(0.070621, 0, 0.2006) |
||
56 | * Eigen::AngleAxisd(angles::from_degrees(90), Eigen::Vector3d::UnitY())
|
||
57 | * Eigen::AngleAxisd(angles::from_degrees(180), Eigen::Vector3d::UnitZ())).inverse();
|
||
58 | eye_distance = 0.143 / 2; |
||
59 | b47687f8 | Robert Haschke | } |
60 | |||
61 | void call(const GoalConstPtr &goal){ |
||
62 | feedback.result = 1;
|
||
63 | |||
64 | hlrc_server::lookattargetGoalConstPtr request = goal; |
||
65 | 60b91de0 | Robert Haschke | const geometry_msgs::PointStamped &p = request->point;
|
66 | 2cf3c285 | Robert Haschke | |
67 | 60b91de0 | Robert Haschke | Eigen::Vector3d target(p.point.x, p.point.y, p.point.z); |
68 | 2cf3c285 | Robert Haschke | try { |
69 | 60b91de0 | Robert Haschke | if (!p.header.frame_id.empty()) { // only consider tf, when frame_id is non-empty |
70 | 87c0fad1 | Robert Haschke | geometry_msgs::TransformStamped base_to_source = |
71 | 2cf3c285 | Robert Haschke | // lookupTransform can throw
|
72 | 60b91de0 | Robert Haschke | tfBuffer.lookupTransform(FLOBI_BASE_LINK, p.header.frame_id, |
73 | p.header.stamp, ros::Duration(0.1)); |
||
74 | 2cf3c285 | Robert Haschke | |
75 | 87c0fad1 | Robert Haschke | target = eig_eyes_to_base * (tf2::transformToEigen(base_to_source) * target); |
76 | 2cf3c285 | Robert Haschke | } else {
|
77 | // otherwise we interpret target directly w.r.t. eye center
|
||
78 | } |
||
79 | } catch (const std::exception &e) {
|
||
80 | 87c0fad1 | Robert Haschke | // Failed to resolve tf
|
81 | ROS_WARN_STREAM_THROTTLE(2, e.what());
|
||
82 | 2cf3c285 | Robert Haschke | result.result = 0;
|
83 | as_.setAborted(result, e.what()); |
||
84 | return;
|
||
85 | } |
||
86 | |||
87 | // compute pan + tilt: let point z-axis of eyes frames towards target
|
||
88 | 87c0fad1 | Robert Haschke | // alternatively, compute inverse kinematics of pan-tilt chain
|
89 | // as here: https://github.com/pal-robotics/head_action
|
||
90 | b47687f8 | Robert Haschke | humotion::GazeState gaze_state; |
91 | 2cf3c285 | Robert Haschke | double distance = target.norm();
|
92 | if (distance > 1e-3) { |
||
93 | 87c0fad1 | Robert Haschke | // normalize vector from eyes-center to target
|
94 | 2cf3c285 | Robert Haschke | target /= distance; |
95 | // pan = rotation about x-axis: angle of projection of target onto yz-plane to z-axis
|
||
96 | 87c0fad1 | Robert Haschke | gaze_state.pan = 90 - angles::to_degrees(atan2(target.z(), target.y()));
|
97 | 2cf3c285 | Robert Haschke | // tilt = rotation about y-axis: angle between target and yz-plane
|
98 | Eigen::Vector2d projection(target.y(), target.z()); |
||
99 | gaze_state.tilt = angles::to_degrees(atan2(target.x(), projection.norm())); |
||
100 | } |
||
101 | // fill in rest of gaze_state
|
||
102 | gaze_state.roll = request->roll; |
||
103 | gaze_state.vergence = angles::to_degrees(atan2(eye_distance, distance)); |
||
104 | b47687f8 | Robert Haschke | |
105 | // use timestamp from request
|
||
106 | 60b91de0 | Robert Haschke | gaze_state.timestamp.set(p.header.stamp.sec, p.header.stamp.nsec); |
107 | b47687f8 | Robert Haschke | gaze_state.gaze_type = humotion::GazeState::GAZETYPE_ABSOLUTE; |
108 | |||
109 | // processing
|
||
110 | as_.publishFeedback(feedback); |
||
111 | |||
112 | // send to application:
|
||
113 | mw->gaze_callback(gaze_state); |
||
114 | |||
115 | if (feedback.result){
|
||
116 | result.result = feedback.result; |
||
117 | as_.setSucceeded(result); |
||
118 | }else{
|
||
119 | as_.setAborted(result); |
||
120 | } |
||
121 | |||
122 | } |
||
123 | }; |