00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00038 #include "motion_adaption/motion_adaption.h"
00039
00040
00041 bool MotionAdaption::getTransforms()
00042 {
00043 try
00044 {
00045
00046 tf_listener_.waitForTransform(world_ref_frame_str_, user_torso_str_, ros::Time(0), ros::Duration(wait_for_tf_));
00047 tf_listener_.lookupTransform(world_ref_frame_str_, user_torso_str_, ros::Time(0), tf_usr_torso_);
00048
00049 tf_listener_.waitForTransform(user_torso_str_, user_head_str_, ros::Time(0), ros::Duration(wait_for_tf_));
00050 tf_listener_.lookupTransform(user_torso_str_, user_head_str_, ros::Time(0), tf_usr_head_);
00051
00052 tf_listener_.waitForTransform(user_torso_str_, user_r_shoulder_str_, ros::Time(0), ros::Duration(wait_for_tf_));
00053 tf_listener_.lookupTransform(user_torso_str_, user_r_shoulder_str_, ros::Time(0), tf_usr_r_shoulder_);
00054
00055 tf_listener_.waitForTransform(user_r_shoulder_str_, user_r_elbow_str_, ros::Time(0), ros::Duration(wait_for_tf_));
00056 tf_listener_.lookupTransform(user_r_shoulder_str_, user_r_elbow_str_, ros::Time(0), tf_usr_r_shoulder_elbow_);
00057
00058 tf_listener_.waitForTransform(user_r_elbow_str_, user_r_hand_str_, ros::Time(0), ros::Duration(wait_for_tf_));
00059 tf_listener_.lookupTransform(user_r_elbow_str_, user_r_hand_str_, ros::Time(0), tf_usr_r_elbow_hand_);
00060
00061 tf_listener_.waitForTransform(user_torso_str_, user_r_elbow_str_, ros::Time(0), ros::Duration(wait_for_tf_));
00062 tf_listener_.lookupTransform(user_torso_str_, user_r_elbow_str_, ros::Time(0), tf_usr_r_elbow_);
00063
00064 tf_listener_.waitForTransform(user_torso_str_, user_r_hand_str_, ros::Time(0), ros::Duration(wait_for_tf_));
00065 tf_listener_.lookupTransform(user_torso_str_, user_r_hand_str_, ros::Time(0), tf_usr_r_hand_);
00066
00067 tf_listener_.waitForTransform(user_torso_str_, user_l_shoulder_str_, ros::Time(0), ros::Duration(wait_for_tf_));
00068 tf_listener_.lookupTransform(user_torso_str_, user_l_shoulder_str_, ros::Time(0), tf_usr_l_shoulder_);
00069
00070 tf_listener_.waitForTransform(user_l_shoulder_str_, user_l_elbow_str_, ros::Time(0), ros::Duration(wait_for_tf_));
00071 tf_listener_.lookupTransform(user_l_shoulder_str_, user_l_elbow_str_, ros::Time(0), tf_usr_l_shoulder_elbow_);
00072
00073 tf_listener_.waitForTransform(user_l_elbow_str_, user_l_hand_str_, ros::Time(0), ros::Duration(wait_for_tf_));
00074 tf_listener_.lookupTransform(user_l_elbow_str_, user_l_hand_str_, ros::Time(0), tf_usr_l_elbow_hand_);
00075
00076 tf_listener_.waitForTransform(user_torso_str_, user_l_elbow_str_, ros::Time(0), ros::Duration(wait_for_tf_));
00077 tf_listener_.lookupTransform(user_torso_str_, user_l_elbow_str_, ros::Time(0), tf_usr_l_elbow_);
00078
00079 tf_listener_.waitForTransform(user_torso_str_, user_l_hand_str_, ros::Time(0), ros::Duration(wait_for_tf_));
00080 tf_listener_.lookupTransform(user_torso_str_, user_l_hand_str_, ros::Time(0), tf_usr_l_hand_);
00081 }
00082 catch (tf::TransformException const &ex)
00083 {
00084 ROS_DEBUG("%s",ex.what());
00085 ROS_WARN("(Step 1) Couldn't get one or more transformations of the user.");
00086 ROS_WARN("No further processing will be done!");
00087 return false;
00088 }
00089 return true;
00090 }
00091