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 <tf_conversions/tf_eigen.h>
00039 #include "motion_adaption/motion_adaption.h"
00040
00041
00042 bool MotionAdaption::adaptTransforms()
00043 {
00044 if(adaptTorso())
00045 {
00046 if(adaptHead())
00047 {
00048 if(scaleUserHandsAndElbows())
00049 {
00050 if(adaptShoulders())
00051 {
00052 if(adaptElbows())
00053 {
00054 if(!adaptHands())
00055 return false;
00056 }
00057 else
00058 return false;
00059 }
00060 else
00061 return false;
00062 }
00063 else
00064 return false;
00065 }
00066 else
00067 return false;
00068 }
00069 else
00070 return false;
00071
00072 return true;
00073 }
00074
00075
00076 bool MotionAdaption::adaptTorso()
00077 {
00078
00079
00080 tf_torso_goal_.setIdentity();
00081
00082 internal_tf.setTransform(tf::StampedTransform(tf_torso_goal_, calc_time, "/ref_frame", "/torso_adapted"));
00083
00084 return true;
00085 }
00086
00087
00088 bool MotionAdaption::adaptHead()
00089 {
00090 try
00091 {
00092 tf_listener_.waitForTransform("/fixed_ref_frame", robot_head_str_, ros::Time(0), ros::Duration(wait_for_tf_));
00093 tf_listener_.lookupTransform("/fixed_ref_frame", robot_head_str_, ros::Time(0), tf_robot_torso_head_);
00094 }
00095 catch (tf::TransformException const &ex)
00096 {
00097 ROS_DEBUG("%s",ex.what());
00098 ROS_WARN("(Step 3.1) Couldn't get the transformation from the fixed_ref_frame to head_goal_frame.");
00099 ROS_WARN("No further processing will be done!");
00100 return false;
00101 }
00102 tf_head_goal_.setIdentity();
00103 tf_head_goal_.setOrigin(tf_robot_torso_head_.getOrigin());
00104
00105 quat_ = tf_usr_head_.getRotation();
00106
00107
00108 tf_head_goal_.setRotation(quat_);
00109
00110
00111 internal_tf.setTransform(tf::StampedTransform(tf_head_goal_, calc_time,"/ref_frame", "/head_adapted"));
00112
00113 return true;
00114 }
00115
00116
00117 bool MotionAdaption::scaleUserHandsAndElbows()
00118 {
00119 user_shoulder_width_ = tf_usr_r_shoulder_.getOrigin().x() + (- tf_usr_l_shoulder_.getOrigin().x());
00120 user_shoulder_height_ = (tf_usr_r_shoulder_.getOrigin().y() + tf_usr_l_shoulder_.getOrigin().y()) / 2.0;
00121 user_upper_arm_length_ = tf_usr_r_shoulder_elbow_.getOrigin().x();
00122 user_arm_length_ = tf_usr_r_shoulder_elbow_.getOrigin().x() + tf_usr_r_elbow_hand_.getOrigin().x();
00123
00124 if (user_shoulder_width_ > 0.0 && user_shoulder_height_ > 0.0 && user_arm_length_ > 0.0)
00125 {
00126 x_norm_ = tf_usr_r_hand_.getOrigin().x() / (user_arm_length_ + 0.5 * user_shoulder_width_);
00127 y_norm_ = tf_usr_r_hand_.getOrigin().y() / (user_arm_length_ + user_shoulder_height_);
00128 z_norm_ = tf_usr_r_hand_.getOrigin().z() / user_arm_length_;
00129 x_adapt_ = x_norm_ * ( robot_arm_length_ + 0.5 * robot_shoulder_width_);
00130 y_adapt_ = y_norm_ * ( robot_arm_length_ + robot_shoulder_heigth_);
00131 z_adapt_ = z_norm_ * robot_arm_length_;
00132 tf_r_hand_scaled_.setOrigin(tf::Vector3(x_adapt_, y_adapt_, z_adapt_));
00133
00134 x_norm_ = tf_usr_l_hand_.getOrigin().x() / (user_arm_length_ + 0.5 * user_shoulder_width_);
00135 y_norm_ = tf_usr_l_hand_.getOrigin().y() / (user_arm_length_ + user_shoulder_height_);
00136 z_norm_ = tf_usr_l_hand_.getOrigin().z() / user_arm_length_;
00137 x_adapt_ = x_norm_ * ( robot_arm_length_ + 0.5 * robot_shoulder_width_);
00138 y_adapt_ = y_norm_ * ( robot_arm_length_ + robot_shoulder_heigth_);
00139 z_adapt_ = z_norm_ * robot_arm_length_;
00140 tf_l_hand_scaled_.setOrigin(tf::Vector3(x_adapt_, y_adapt_, z_adapt_));
00141
00142 x_norm_ = tf_usr_r_elbow_.getOrigin().x() / (user_upper_arm_length_ + 0.5 * user_shoulder_width_);
00143 y_norm_ = tf_usr_r_elbow_.getOrigin().y() / (user_upper_arm_length_ + user_shoulder_height_);
00144 z_norm_ = tf_usr_r_elbow_.getOrigin().z() / user_upper_arm_length_;
00145 x_adapt_ = x_norm_ * ( robot_upper_arm_length_ + 0.5 * robot_shoulder_width_);
00146 y_adapt_ = y_norm_ * ( robot_upper_arm_length_ + robot_shoulder_heigth_);
00147 z_adapt_ = z_norm_ * robot_upper_arm_length_;
00148 tf_r_elbow_scaled_.setOrigin(tf::Vector3(x_adapt_, y_adapt_, z_adapt_));
00149
00150 x_norm_ = tf_usr_l_elbow_.getOrigin().x() / (user_upper_arm_length_ + 0.5 * user_shoulder_width_);
00151 y_norm_ = tf_usr_l_elbow_.getOrigin().y() / (user_upper_arm_length_ + user_shoulder_height_);
00152 z_norm_ = tf_usr_l_elbow_.getOrigin().z() / user_upper_arm_length_;
00153 x_adapt_ = x_norm_ * ( robot_upper_arm_length_ + 0.5 * robot_shoulder_width_);
00154 y_adapt_ = y_norm_ * ( robot_upper_arm_length_ + robot_shoulder_heigth_);
00155 z_adapt_ = z_norm_ * robot_upper_arm_length_;
00156 tf_l_elbow_scaled_.setOrigin(tf::Vector3(x_adapt_, y_adapt_, z_adapt_));
00157
00158
00159 internal_tf.setTransform(tf::StampedTransform(tf_r_elbow_scaled_, calc_time, "/ref_frame", "/r_elbow_scaled"));
00160
00161 internal_tf.setTransform(tf::StampedTransform(tf_r_hand_scaled_, calc_time, "/ref_frame", "/r_hand_scaled"));
00162
00163 internal_tf.setTransform(tf::StampedTransform(tf_l_elbow_scaled_, calc_time, "/ref_frame", "/l_elbow_scaled"));
00164
00165 internal_tf.setTransform(tf::StampedTransform(tf_l_hand_scaled_, calc_time, "/ref_frame", "/l_hand_scaled"));
00166 }
00167 else
00168 {
00169 ROS_WARN("(Step 3.3) User's body proportions are not valid.");
00170 ROS_WARN("No further processing will be done!");
00171 return false;
00172 }
00173 return true;
00174 }
00175
00176
00177 bool MotionAdaption::adaptShoulders()
00178 {
00179
00180 try
00181 {
00182 tf_listener_.waitForTransform("/fixed_ref_frame", robot_r_shoulder_str_, ros::Time(0),
00183 ros::Duration(wait_for_tf_));
00184 tf_listener_.lookupTransform("/fixed_ref_frame", robot_r_shoulder_str_, ros::Time(0),
00185 tf_robot_torso_r_shoulder_);
00186 tf_listener_.waitForTransform("/fixed_ref_frame", robot_l_shoulder_str_, ros::Time(0),
00187 ros::Duration(wait_for_tf_));
00188 tf_listener_.lookupTransform("/fixed_ref_frame", robot_l_shoulder_str_, ros::Time(0),
00189 tf_robot_torso_l_shoulder_);
00190 tf_listener_.waitForTransform(robot_r_shoulder_str_, robot_l_shoulder_str_, ros::Time(0),
00191 ros::Duration(wait_for_tf_));
00192 tf_listener_.lookupTransform(robot_r_shoulder_str_, robot_l_shoulder_str_, ros::Time(0),
00193 tf_robot_r_shoulder_l_shoulder_);
00194 tf_listener_.waitForTransform(robot_r_shoulder_str_, robot_r_elbow_str_, ros::Time(0), ros::Duration(wait_for_tf_));
00195 tf_listener_.lookupTransform(robot_r_shoulder_str_, robot_r_elbow_str_, ros::Time(0), tf_robot_r_shoulder_r_elbow_);
00196 tf_listener_.waitForTransform(robot_r_elbow_str_, robot_r_hand_str_, ros::Time(0), ros::Duration(wait_for_tf_));
00197 tf_listener_.lookupTransform(robot_r_elbow_str_, robot_r_hand_str_, ros::Time(0), tf_robot_r_elbow_r_hand_);
00198 }
00199 catch (tf::TransformException const &ex)
00200 {
00201 ROS_DEBUG("%s",ex.what());
00202 ROS_WARN("(Step 3.4.1) Couldn't get one or more transformations of the robot to calculate body measurements.");
00203 ROS_WARN("No further processing will be done!");
00204 return false;
00205 }
00206 robot_shoulder_heigth_ = sqrt(pow(tf_robot_torso_r_shoulder_.getOrigin()[
00207 tf_robot_torso_r_shoulder_.getOrigin().absolute().maxAxis()], 2));
00208 robot_shoulder_width_ = sqrt(pow(tf_robot_r_shoulder_l_shoulder_.getOrigin()[
00209 tf_robot_r_shoulder_l_shoulder_.getOrigin().absolute().maxAxis()], 2));
00210 robot_upper_arm_length_ = sqrt(tf_robot_r_shoulder_r_elbow_.getOrigin().length2());
00211 robot_lower_arm_length_ = sqrt(tf_robot_r_elbow_r_hand_.getOrigin().length2());
00212 robot_arm_length_ = robot_upper_arm_length_ + robot_lower_arm_length_;
00213 ROS_DEBUG_THROTTLE(1.0, "robot_shoulder_heigth = %f, robot_shoulder_width = %f, robot_arm_length = %f",
00214 robot_shoulder_heigth_, robot_shoulder_width_, robot_arm_length_);
00215
00216 tf_r_shoulder_scaled_.setOrigin(tf_robot_torso_r_shoulder_.getOrigin());
00217 tf_l_shoulder_scaled_.setOrigin(tf_robot_torso_l_shoulder_.getOrigin());
00218
00219 internal_tf.setTransform(tf::StampedTransform(tf_r_shoulder_scaled_, calc_time,"/ref_frame", "/r_robot_shoulder"));
00220
00221 internal_tf.setTransform(tf::StampedTransform(tf_l_shoulder_scaled_, calc_time,"/ref_frame", "/l_robot_shoulder"));
00222
00223
00224
00225
00226
00227
00228
00229
00230
00231
00232
00233
00234 try
00235 {
00236
00237 internal_tf.lookupTransform("/r_robot_shoulder", "/r_elbow_scaled", ros::Time(0), tf_r_shoulder_elbow_);
00238
00239 internal_tf.lookupTransform("/r_robot_shoulder", "/r_hand_scaled", ros::Time(0), tf_r_shoulder_hand_);
00240
00241 internal_tf.lookupTransform("/l_robot_shoulder", "/l_elbow_scaled", ros::Time(0), tf_l_shoulder_elbow_);
00242
00243 internal_tf.lookupTransform("/l_robot_shoulder", "/l_hand_scaled", ros::Time(0), tf_l_shoulder_hand_);
00244 }
00245 catch (tf::TransformException const &ex)
00246 {
00247 ROS_DEBUG("%s",ex.what());
00248 ROS_WARN("(Step 3.4.2) Couldn't get one or more transformations from the shoulders to the hands and elbows.");
00249 ROS_WARN("No further processing will be done!");
00250 return false;
00251 }
00252
00253
00254 vec_shoulder_elbow_ = tf_r_shoulder_elbow_.getOrigin();
00255 vec_shoulder_hand_ = tf_r_shoulder_hand_.getOrigin();
00256 if(vec_shoulder_hand_.angle(vec_shoulder_elbow_) < 0.15708 && !vec_r_elbow_hand_valid_.isZero())
00257 {
00258 ROS_DEBUG_THROTTLE(0.1, "valid right hand vector is used (angle between vectors: %f).",
00259 vec_shoulder_hand_.angle(vec_shoulder_elbow_));
00260 vec_shoulder_hand_ = vec_shoulder_elbow_ + vec_r_elbow_hand_valid_;
00261 r_elbow_extended_ = true;
00262 }
00263 else
00264 {
00265 vec_r_elbow_hand_valid_ = vec_shoulder_hand_ - vec_shoulder_elbow_;
00266 r_elbow_extended_ = false;
00267 }
00268 vec_normal_ = vec_shoulder_hand_.cross(vec_shoulder_elbow_);
00269 vec_helper_ = vec_normal_.cross(vec_shoulder_hand_);
00270 vec_shoulder_hand_.normalize();
00271 vec_helper_.normalize();
00272 vec_normal_.normalize();
00273 mat_orientation_.setValue(vec_shoulder_hand_.x(), vec_helper_.x(), vec_normal_.x(),
00274 vec_shoulder_hand_.y(), vec_helper_.y(), vec_normal_.y(),
00275 vec_shoulder_hand_.z(), vec_helper_.z(), vec_normal_.z());
00276 tf_r_shoulder_goal_.setBasis(mat_orientation_);
00277
00278 internal_tf.setTransform(tf::StampedTransform(tf_r_shoulder_goal_, calc_time, "/r_robot_shoulder", "/r_shoulder_adapted"));
00279
00280
00281 vec_shoulder_elbow_ = tf_l_shoulder_elbow_.getOrigin();
00282 vec_shoulder_hand_ = tf_l_shoulder_hand_.getOrigin();
00283 if(vec_shoulder_hand_.angle(vec_shoulder_elbow_) < 0.15708 && !vec_l_elbow_hand_valid_.isZero())
00284 {
00285 ROS_DEBUG_THROTTLE(0.1, "valid right hand vector is used (angle between vectors: %f).",
00286 vec_shoulder_hand_.angle(vec_shoulder_elbow_));
00287 vec_shoulder_hand_ = vec_shoulder_elbow_ + vec_l_elbow_hand_valid_;
00288 l_elbow_extended_ = true;
00289 }
00290 else
00291 {
00292 vec_l_elbow_hand_valid_ = vec_shoulder_hand_ - vec_shoulder_elbow_;
00293 l_elbow_extended_ = false;
00294 }
00295 vec_normal_ = vec_shoulder_hand_.cross(vec_shoulder_elbow_);
00296 vec_helper_ = vec_normal_.cross(vec_shoulder_hand_);
00297 vec_shoulder_hand_.normalize();
00298 vec_helper_.normalize();
00299 vec_normal_.normalize();
00300 mat_orientation_.setValue(vec_shoulder_hand_.x(), vec_helper_.x(), vec_normal_.x(),
00301 vec_shoulder_hand_.y(), vec_helper_.y(), vec_normal_.y(),
00302 vec_shoulder_hand_.z(), vec_helper_.z(), vec_normal_.z());
00303 tf_l_shoulder_goal_.setBasis(mat_orientation_);
00304
00305 internal_tf.setTransform(tf::StampedTransform(tf_l_shoulder_goal_, calc_time, "/l_robot_shoulder", "/l_shoulder_adapted"));
00306 return true;
00307 }
00308
00309
00310 bool MotionAdaption::adaptElbows()
00311 {
00312
00313 limb_length_ = tf_r_shoulder_hand_.getOrigin().length();
00314 if (limb_length_ >= robot_arm_length_|| r_elbow_extended_)
00315 {
00316 elbow_x_ = robot_upper_arm_length_;
00317 elbow_y_ = 0.0;
00318 }
00319 else if (limb_length_ < 1e-6)
00320 {
00321 elbow_x_ = 0.0;
00322 elbow_y_ = robot_upper_arm_length_;
00323 }
00324 else
00325 {
00326 elbow_x_ = (pow(limb_length_, 2) - pow(robot_lower_arm_length_, 2) + pow(robot_upper_arm_length_, 2)) /
00327 ( 2 * limb_length_);
00328 elbow_y_ = sqrt(pow(robot_upper_arm_length_, 2) - pow(elbow_x_, 2));
00329 }
00330 tf_r_elbow_pos_.setOrigin(tf::Vector3(elbow_x_, elbow_y_, 0.0));
00331
00332 internal_tf.setTransform(tf::StampedTransform(tf_r_elbow_pos_, calc_time, "/r_shoulder_adapted", "/r_elbow_pos"));
00333
00334 limb_length_ = tf_l_shoulder_hand_.getOrigin().length();
00335 if (limb_length_ >= robot_arm_length_ || l_elbow_extended_)
00336 {
00337 elbow_x_ = robot_upper_arm_length_;
00338 elbow_y_ = 0.0;
00339 }
00340 else if (limb_length_ < 1e-6)
00341 {
00342 elbow_x_ = 0.0;
00343 elbow_y_ = robot_upper_arm_length_;
00344 }
00345 else
00346 {
00347 elbow_x_ = (pow(limb_length_, 2) - pow(robot_lower_arm_length_, 2) + pow(robot_upper_arm_length_, 2)) /
00348 ( 2 * limb_length_);
00349 elbow_y_ = sqrt(pow(robot_upper_arm_length_, 2) - pow(elbow_x_, 2));
00350 }
00351 tf_l_elbow_pos_.setOrigin(tf::Vector3(elbow_x_, elbow_y_, 0.0));
00352
00353 internal_tf.setTransform(tf::StampedTransform(tf_l_elbow_pos_, calc_time, "/l_shoulder_adapted", "/l_elbow_pos"));
00354
00355
00356 try
00357 {
00358
00359 internal_tf.lookupTransform("/r_elbow_pos", "/r_hand_scaled", ros::Time(0), tf_r_elbow_hand_);
00360
00361 internal_tf.lookupTransform("/l_elbow_pos", "/l_hand_scaled", ros::Time(0), tf_l_elbow_hand_);
00362 }
00363 catch (tf::TransformException ex)
00364 {
00365 ROS_DEBUG("%s",ex.what());
00366 ROS_WARN("(Step 3.5) Couldn't get one or more transformations from the elbow to the hands.");
00367 ROS_WARN("No further processing will be done!");
00368 return false;
00369 }
00370
00371 if(l_elbow_extended_ == true)
00372 tf_l_elbow_hand_.setOrigin(tf::Vector3(robot_lower_arm_length_, 0.0, 0.0));
00373
00374 vec_elbow_hand_ = tf_r_elbow_hand_.getOrigin();
00375 vec_normal_ = tf::Vector3(0.0, 0.0, 1.0);
00376 vec_helper_ = vec_normal_.cross(vec_elbow_hand_);
00377 vec_elbow_hand_.normalize();
00378 vec_normal_.normalize();
00379 vec_helper_.normalize();
00380 mat_orientation_.setValue(vec_elbow_hand_.x(), vec_helper_.x(), vec_normal_.x(),
00381 vec_elbow_hand_.y(), vec_helper_.y(), vec_normal_.y(),
00382 vec_elbow_hand_.z(), vec_helper_.z(), vec_normal_.z());
00383 tf_r_elbow_goal_.setOrigin(tf_r_elbow_pos_.getOrigin());
00384 tf_r_elbow_goal_.setBasis(mat_orientation_);
00385
00386
00387 internal_tf.setTransform(tf::StampedTransform(tf_r_elbow_goal_, calc_time, "/r_shoulder_adapted", "/r_elbow_adapted"));
00388 vec_elbow_hand_ = tf_l_elbow_hand_.getOrigin();
00389 vec_normal_ = tf::Vector3(0.0, 0.0, 1.0);
00390 vec_helper_ = vec_normal_.cross(vec_elbow_hand_);
00391 vec_elbow_hand_.normalize();
00392 vec_normal_.normalize();
00393 vec_helper_.normalize();
00394 mat_orientation_.setValue(vec_elbow_hand_.x(), vec_helper_.x(), vec_normal_.x(),
00395 vec_elbow_hand_.y(), vec_helper_.y(), vec_normal_.y(),
00396 vec_elbow_hand_.z(), vec_helper_.z(), vec_normal_.z());
00397 tf_l_elbow_goal_.setOrigin(tf_l_elbow_pos_.getOrigin());
00398 tf_l_elbow_goal_.setBasis(mat_orientation_);
00399
00400 internal_tf.setTransform(tf::StampedTransform(tf_l_elbow_goal_, calc_time, "/l_shoulder_adapted", "/l_elbow_adapted"));
00401 return true;
00402 }
00403
00404
00405 bool MotionAdaption::adaptHands()
00406 {
00407 try
00408 {
00409
00410 internal_tf.lookupTransform("/ref_frame", "/r_elbow_adapted", ros::Time(0), tf_r_elbow_orient_);
00411
00412 internal_tf.lookupTransform("/ref_frame", "/l_elbow_adapted", ros::Time(0), tf_l_elbow_orient_);
00413 }
00414 catch (tf::TransformException const &ex)
00415 {
00416 ROS_DEBUG("%s",ex.what());
00417 ROS_WARN("(Step 3.6) Couldn't get one or more transformations from the ref frame to the elbows.");
00418 ROS_WARN("No further processing will be done!");
00419 return false;
00420 }
00421 tf_r_hand_adjusted_.setIdentity();
00422 tf_r_hand_adjusted_.setOrigin(tf::Vector3(robot_lower_arm_length_, 0.0, 0.0));
00423
00424 internal_tf.setTransform(tf::StampedTransform(tf_r_hand_adjusted_, calc_time, "/r_elbow_adapted", "/r_hand_adapted"));
00425 tf_l_hand_goal_.setIdentity();
00426 tf_l_hand_goal_.setOrigin(tf::Vector3(robot_lower_arm_length_, 0.0, 0.0));
00427
00428 internal_tf.setTransform(tf::StampedTransform(tf_l_hand_goal_, calc_time, "/l_elbow_adapted", "/l_hand_adapted"));
00429 return true;
00430 }
00431