00001 /* 00002 * Software License Agreement (Modified BSD License) 00003 * 00004 * Copyright (c) 2011, PAL Robotics, S.L. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of PAL Robotics, S.L. nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 */ 00034 00038 #include "motion_adaption/motion_adaption.h" 00039 00040 00041 void MotionAdaption::publishData() 00042 { 00043 // Torso 00044 pose_.header.stamp = ros::Time::now(); 00045 pose_.header.frame_id = "/torso_adapted"; 00046 pose_.pose.position.x = tf_torso_goal_.getOrigin().x(); 00047 pose_.pose.position.y = tf_torso_goal_.getOrigin().y(); 00048 pose_.pose.position.z = tf_torso_goal_.getOrigin().z(); 00049 pose_.pose.orientation.x = tf_torso_goal_.getRotation().x(); 00050 pose_.pose.orientation.y = tf_torso_goal_.getRotation().y(); 00051 pose_.pose.orientation.z = tf_torso_goal_.getRotation().z(); 00052 pose_.pose.orientation.w = tf_torso_goal_.getRotation().w(); 00053 pub_torso_pose_.publish(pose_); 00054 00055 // Head 00056 pose_.header.stamp = ros::Time::now(); 00057 pose_.header.frame_id = "/head_adapted"; 00058 pose_.pose.position.x = tf_head_goal_.getOrigin().x(); 00059 pose_.pose.position.y = tf_head_goal_.getOrigin().y(); 00060 pose_.pose.position.z = tf_head_goal_.getOrigin().z(); 00061 pose_.pose.orientation.x = tf_head_goal_.getRotation().x(); 00062 pose_.pose.orientation.y = tf_head_goal_.getRotation().y(); 00063 pose_.pose.orientation.z = tf_head_goal_.getRotation().z(); 00064 pose_.pose.orientation.w = tf_head_goal_.getRotation().w(); 00065 pub_head_pose_.publish(pose_); 00066 00067 // Right elbow 00068 pose_.header.stamp = ros::Time::now(); 00069 pose_.header.frame_id = "/r_elbow_adapted"; 00070 pose_.pose.position.x = tf_r_elbow_goal_.getOrigin().x(); 00071 pose_.pose.position.y = tf_r_elbow_goal_.getOrigin().y(); 00072 pose_.pose.position.z = tf_r_elbow_goal_.getOrigin().z(); 00073 pose_.pose.orientation.x = tf_r_elbow_goal_.getRotation().x(); 00074 pose_.pose.orientation.y = tf_r_elbow_goal_.getRotation().y(); 00075 pose_.pose.orientation.z = tf_r_elbow_goal_.getRotation().z(); 00076 pose_.pose.orientation.w = tf_r_elbow_goal_.getRotation().w(); 00077 pub_r_elbow_pose_.publish(pose_); 00078 00079 // Right hand 00080 pose_.header.stamp = ros::Time::now(); 00081 pose_.header.frame_id = "/r_hand_adapted"; 00082 pose_.pose.position.x = tf_r_hand_goal_.getOrigin().x(); 00083 pose_.pose.position.y = tf_r_hand_goal_.getOrigin().y(); 00084 pose_.pose.position.z = tf_r_hand_goal_.getOrigin().z(); 00085 pose_.pose.orientation.x = tf_r_hand_goal_.getRotation().x(); 00086 pose_.pose.orientation.y = tf_r_hand_goal_.getRotation().y(); 00087 pose_.pose.orientation.z = tf_r_hand_goal_.getRotation().z(); 00088 pose_.pose.orientation.w = tf_r_hand_goal_.getRotation().w(); 00089 pub_r_hand_pose_.publish(pose_); 00090 00091 // Left elbow 00092 pose_.header.stamp = ros::Time::now(); 00093 pose_.header.frame_id = "/l_elbow_adapted"; 00094 pose_.pose.position.x = tf_l_elbow_goal_.getOrigin().x(); 00095 pose_.pose.position.y = tf_l_elbow_goal_.getOrigin().y(); 00096 pose_.pose.position.z = tf_l_elbow_goal_.getOrigin().z(); 00097 pose_.pose.orientation.x = tf_l_elbow_goal_.getRotation().x(); 00098 pose_.pose.orientation.y = tf_l_elbow_goal_.getRotation().y(); 00099 pose_.pose.orientation.z = tf_l_elbow_goal_.getRotation().z(); 00100 pose_.pose.orientation.w = tf_l_elbow_goal_.getRotation().w(); 00101 pub_l_elbow_pose_.publish(pose_); 00102 00103 // Left hand 00104 pose_.header.stamp = ros::Time::now(); 00105 pose_.header.frame_id = "/l_hand_adapted"; 00106 pose_.pose.position.x = tf_l_hand_goal_.getOrigin().x(); 00107 pose_.pose.position.y = tf_l_hand_goal_.getOrigin().y(); 00108 pose_.pose.position.z = tf_l_hand_goal_.getOrigin().z(); 00109 pose_.pose.orientation.x = tf_l_hand_goal_.getRotation().x(); 00110 pose_.pose.orientation.y = tf_l_hand_goal_.getRotation().y(); 00111 pose_.pose.orientation.z = tf_l_hand_goal_.getRotation().z(); 00112 pose_.pose.orientation.w = tf_l_hand_goal_.getRotation().w(); 00113 pub_l_hand_pose_.publish(pose_); 00114 } 00115