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