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
00037 #include "motion_adaption/motion_adaption.h"
00038
00039
00040 void MotionAdaption::setGoals()
00041 {
00042
00043 ros::Time publish_time = ros::Time::now();
00044 std::vector<tf::StampedTransform> tf_transforms(6);
00045
00046
00047 tf::StampedTransform out_tf;
00048
00049 tf_torso_goal_.setOrigin(tf::Vector3(0.0, 0.0, 0.0));
00050
00051 quat_.setRPY(torso_goal_rot_vec_[0], torso_goal_rot_vec_[1], torso_goal_rot_vec_[2]);
00052 tf_torso_goal_.setRotation(quat_);
00053
00054 out_tf = tf_torso_goal_;
00055 out_tf.stamp_ = publish_time;
00056 out_tf.frame_id_ = "/ref_frame";
00057 out_tf.child_frame_id_ = "/torso_goal";
00058 tf_transforms[0] = out_tf;
00059
00060
00061 tf_head_goal_.setOrigin(tf::Vector3(0.0, 0.0, 0.0));
00062
00063 quat_.setRPY(head_goal_rot_vec_[0], head_goal_rot_vec_[1], head_goal_rot_vec_[2]);
00064 tf_head_goal_.setRotation(quat_);
00065 internal_tf.setTransform(tf::StampedTransform(tf_head_goal_, calc_time, "/head_adapted", "/head_goal"));
00066 internal_tf.lookupTransform("/ref_frame", "/head_goal", ros::Time(0), out_tf);
00067
00068 out_tf.stamp_ = publish_time;
00069 out_tf.frame_id_ = "/ref_frame";
00070 out_tf.child_frame_id_ = "/head_goal";
00071 tf_transforms[1] = out_tf;
00072
00073
00074 tf_r_elbow_goal_.setOrigin(tf::Vector3(0.0, 0.0, 0.0));
00075
00076 quat_.setRPY(r_elbow_goal_rot_vec_[0], r_elbow_goal_rot_vec_[1], r_elbow_goal_rot_vec_[2]);
00077 tf_r_elbow_goal_.setRotation(quat_);
00078 internal_tf.setTransform(tf::StampedTransform(tf_r_elbow_goal_, calc_time, "/r_elbow_adapted", "/r_elbow_goal"));
00079 internal_tf.lookupTransform("/ref_frame", "/r_elbow_goal", ros::Time(0), out_tf);
00080
00081 out_tf.stamp_ = publish_time;
00082 out_tf.frame_id_ = "/ref_frame";
00083 out_tf.child_frame_id_ = "/r_elbow_goal";
00084 tf_transforms[2] = out_tf;
00085
00086
00087 tf_l_elbow_goal_.setOrigin(tf::Vector3(0.0, 0.0, 0.0));
00088
00089 quat_.setRPY(l_elbow_goal_rot_vec_[0], l_elbow_goal_rot_vec_[1], l_elbow_goal_rot_vec_[2]);
00090 tf_l_elbow_goal_.setRotation(quat_);
00091 internal_tf.setTransform(tf::StampedTransform(tf_l_elbow_goal_, calc_time, "/l_elbow_adapted", "/l_elbow_goal"));
00092 internal_tf.lookupTransform("/ref_frame", "/l_elbow_goal", ros::Time(0), out_tf);
00093
00094 out_tf.stamp_ = publish_time;
00095 out_tf.frame_id_ = "/ref_frame";
00096 out_tf.child_frame_id_ = "/l_elbow_goal";
00097 tf_transforms[3] = out_tf;
00098
00099
00100 tf_r_hand_goal_.setOrigin(tf::Vector3(0.0, 0.0, 0.0));
00101
00102 quat_.setRPY(r_hand_goal_rot_vec_[0], r_hand_goal_rot_vec_[1], r_hand_goal_rot_vec_[2]);
00103 tf_r_hand_goal_.setRotation(quat_);
00104
00105 internal_tf.setTransform(tf::StampedTransform(tf_r_hand_goal_, calc_time, "/r_hand_adapted", "/r_hand_goal"));
00106 internal_tf.lookupTransform("/ref_frame", "/r_hand_goal", ros::Time(0), out_tf);
00107
00108 out_tf.stamp_ = publish_time;
00109 out_tf.frame_id_ = "/ref_frame";
00110 out_tf.child_frame_id_ = "/r_hand_goal";
00111 tf_transforms[4] = out_tf;
00112
00113
00114 tf_l_hand_goal_.setOrigin(tf::Vector3(0.0, 0.0, 0.0));
00115
00116 quat_.setRPY(l_hand_goal_rot_vec_[0], l_hand_goal_rot_vec_[1], l_hand_goal_rot_vec_[2]);
00117 tf_l_hand_goal_.setRotation(quat_);
00118
00119 internal_tf.setTransform(tf::StampedTransform(tf_l_hand_goal_, calc_time, "/l_hand_adapted", "/l_hand_goal"));
00120 internal_tf.lookupTransform("/ref_frame", "/l_hand_goal", ros::Time(0), out_tf);
00121
00122 out_tf.stamp_ = publish_time;
00123 out_tf.frame_id_ = "/ref_frame";
00124 out_tf.child_frame_id_ = "/l_hand_goal";
00125 tf_transforms[5] = out_tf;
00126
00127
00128 tf_broadcaster_.sendTransform(tf_transforms);
00129
00130
00131
00132
00133
00134
00135
00136
00137
00138
00139
00140
00141
00142
00143
00144
00145
00146
00147
00148
00149 }