Go to the documentation of this file.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 <LinearMath/btVector3.h>
00038 #include <geometry_msgs/PoseStamped.h>
00039 #include <ros/ros.h>
00040 #include <tf/transform_broadcaster.h>
00041 #include <tf/transform_datatypes.h>
00042 #include <tf/transform_listener.h>
00043
00051 class MotionAdaption
00052 {
00053 public:
00054 MotionAdaption();
00055 ~MotionAdaption();
00056
00061 void adapt();
00062
00063 private:
00064
00065 tf::Transformer internal_tf;
00066 ros::Time calc_time;
00067
00074 bool getTransforms();
00075
00081 bool setRefFrame();
00082
00088 bool adaptTransforms();
00089
00096 bool adaptTorso();
00097
00104 bool adaptHead();
00105
00112 bool scaleUserHandsAndElbows();
00113
00121 bool adaptShoulders();
00122
00131 bool adaptElbows();
00132
00139 bool adaptHands();
00140
00145 void setGoals();
00146
00151 void publishData();
00152
00153 ros::NodeHandle nh_, nh_private_;
00154
00155
00156 tf::TransformListener tf_listener_;
00157
00158
00159 tf::TransformBroadcaster tf_broadcaster_;
00160
00161
00162 double wait_for_tf_;
00163
00164
00165 ros::Publisher pub_torso_pose_;
00166 ros::Publisher pub_head_pose_;
00167 ros::Publisher pub_r_elbow_pose_;
00168 ros::Publisher pub_r_hand_pose_;
00169 ros::Publisher pub_l_elbow_pose_;
00170 ros::Publisher pub_l_hand_pose_;
00171 geometry_msgs::PoseStamped pose_;
00172
00173
00174 std::string world_ref_frame_str_;
00175 std::string user_torso_str_;
00176 std::string user_head_str_;
00177 std::string user_r_shoulder_str_;
00178 std::string user_r_elbow_str_;
00179 std::string user_r_hand_str_;
00180 std::string user_l_shoulder_str_;
00181 std::string user_l_elbow_str_;
00182 std::string user_l_hand_str_;
00183 std::string robot_base_str_;
00184 std::string robot_ref_torso_str_;
00185 std::string robot_torso_str_;
00186 std::string robot_head_str_;
00187 std::string robot_r_shoulder_str_;
00188 std::string robot_r_elbow_str_;
00189 std::string robot_r_hand_str_;
00190 std::string robot_l_shoulder_str_;
00191 std::string robot_l_elbow_str_;
00192 std::string robot_l_hand_str_;
00193
00194
00195 btVector3 ref_frame_rot_vec_;
00196 btVector3 torso_goal_rot_vec_;
00197 btVector3 head_goal_rot_vec_;
00198 btVector3 r_elbow_goal_rot_vec_;
00199 btVector3 r_hand_goal_rot_vec_;
00200 btVector3 l_elbow_goal_rot_vec_;
00201 btVector3 l_hand_goal_rot_vec_;
00202
00203 tf::StampedTransform tf_usr_torso_;
00204 tf::StampedTransform tf_usr_head_;
00205 tf::StampedTransform tf_usr_r_shoulder_;
00206 tf::StampedTransform tf_usr_r_shoulder_elbow_;
00207 tf::StampedTransform tf_usr_r_shoulder_hand_;
00208 tf::StampedTransform tf_usr_r_elbow_;
00209 tf::StampedTransform tf_usr_r_elbow_hand_;
00210 tf::StampedTransform tf_usr_r_hand_;
00211 tf::StampedTransform tf_usr_l_shoulder_;
00212 tf::StampedTransform tf_usr_l_shoulder_elbow_;
00213 tf::StampedTransform tf_usr_l_shoulder_hand_;
00214 tf::StampedTransform tf_usr_l_elbow_;
00215 tf::StampedTransform tf_usr_l_elbow_hand_;
00216 tf::StampedTransform tf_usr_l_hand_;
00217 tf::StampedTransform tf_robot_ref_torso_;
00218 tf::StampedTransform tf_robot_torso_torso_;
00219 tf::StampedTransform tf_robot_torso_head_;
00220 tf::StampedTransform tf_robot_torso_r_shoulder_;
00221 tf::StampedTransform tf_robot_torso_l_shoulder_;
00222 tf::StampedTransform tf_robot_r_shoulder_l_shoulder_;
00223 tf::StampedTransform tf_robot_r_shoulder_r_elbow_;
00224 tf::StampedTransform tf_robot_r_elbow_r_hand_;
00225
00226 tf::StampedTransform tf_ref_frame_;
00227 tf::StampedTransform tf_torso_aligned_;
00228 tf::StampedTransform tf_torso_goal_;
00229 tf::StampedTransform tf_head_goal_;
00230 tf::StampedTransform tf_r_shoulder_scaled_;
00231 tf::StampedTransform tf_r_shoulder_goal_;
00232 tf::StampedTransform tf_r_shoulder_elbow_;
00233 tf::StampedTransform tf_r_shoulder_hand_;
00234 tf::StampedTransform tf_r_elbow_scaled_;
00235 tf::StampedTransform tf_r_elbow_pos_;
00236 tf::StampedTransform tf_r_elbow_orient_;
00237 tf::StampedTransform tf_r_elbow_hand_;
00238 tf::StampedTransform tf_r_elbow_goal_;
00239 tf::StampedTransform tf_r_hand_scaled_;
00240 tf::StampedTransform tf_r_hand_adjusted_;
00241 tf::StampedTransform tf_r_hand_goal_;
00242 tf::StampedTransform tf_l_shoulder_scaled_;
00243 tf::StampedTransform tf_l_shoulder_goal_;
00244 tf::StampedTransform tf_l_shoulder_elbow_;
00245 tf::StampedTransform tf_l_shoulder_hand_;
00246 tf::StampedTransform tf_l_elbow_scaled_;
00247 tf::StampedTransform tf_l_elbow_pos_;
00248 tf::StampedTransform tf_l_elbow_orient_;
00249 tf::StampedTransform tf_l_elbow_hand_;
00250 tf::StampedTransform tf_l_elbow_goal_;
00251 tf::StampedTransform tf_l_hand_scaled_;
00252 tf::StampedTransform tf_l_hand_goal_;
00253
00254 tf::Quaternion quat_, quat_adjust_;
00255
00256 double robot_shoulder_heigth_, robot_shoulder_width_, robot_head_height_, robot_shoulder_x_offset_;
00257 double robot_upper_arm_length_, robot_lower_arm_length_, robot_arm_length_;
00258 double user_shoulder_width_, user_shoulder_height_, user_upper_arm_length_, user_arm_length_;
00259 double x_norm_, y_norm_, z_norm_, x_adapt_, y_adapt_, z_adapt_, elbow_x_, elbow_y_, limb_length_;
00260
00261 btVector3 vec_shoulder_elbow_, vec_shoulder_hand_, vec_elbow_hand_, vec_normal_, vec_helper_;
00262 btVector3 vec_r_shoulder_elbow_valid_, vec_l_shoulder_elbow_valid_;
00263 btVector3 vec_r_elbow_hand_valid_, vec_l_elbow_hand_valid_;
00264 bool r_elbow_extended_, l_elbow_extended_;
00265 btMatrix3x3 mat_orientation_;
00266 };