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 #ifndef NAO_FOOTPRINT_HPP
00019 #define NAO_FOOTPRINT_HPP
00020
00021
00022
00023
00024 #include <tf2/LinearMath/Transform.h>
00025 #include <geometry_msgs/Transform.h>
00026 #include <tf2_geometry_msgs/tf2_geometry_msgs.h>
00027
00028
00029
00030
00031 #include "../helpers/transform_helpers.hpp"
00032
00033 namespace naoqi
00034 {
00035 namespace converter
00036 {
00037 namespace nao
00038 {
00039
00040 inline void addBaseFootprint( boost::shared_ptr<tf2_ros::Buffer> tf2_buffer, std::vector<geometry_msgs::TransformStamped>& tf_transforms, const ros::Time& time )
00041 {
00042 bool canTransform = tf2_buffer->canTransform("odom", "l_sole", time, ros::Duration(0.1) );
00043 if (!canTransform)
00044 {
00045 ROS_ERROR_STREAM("Do not calculate NAO Footprint, no transform possible " << time);
00046 return;
00047 }
00048
00049 geometry_msgs::TransformStamped tf_odom_to_base, tf_odom_to_left_foot, tf_odom_to_right_foot;
00050 try {
00051
00052 tf_odom_to_left_foot = tf2_buffer->lookupTransform("odom", "l_sole", time );
00053 tf_odom_to_right_foot = tf2_buffer->lookupTransform("odom", "r_sole", time );
00054 tf_odom_to_base = tf2_buffer->lookupTransform("odom", "base_link", time );
00055 } catch (const tf2::TransformException& ex){
00056 ROS_ERROR("NAO Footprint error %s",ex.what());
00057 return ;
00058 }
00059
00060
00061 tf2::Vector3 new_origin(
00062 float(tf_odom_to_right_foot.transform.translation.x + tf_odom_to_left_foot.transform.translation.x)/2.0,
00063 float(tf_odom_to_right_foot.transform.translation.y + tf_odom_to_left_foot.transform.translation.y)/2.0,
00064 std::min(tf_odom_to_left_foot.transform.translation.z, tf_odom_to_right_foot.transform.translation.z)
00065 );
00066
00067
00068 double yaw = helpers::transform::getYaw( tf_odom_to_base.transform ) ;
00069 tf2::Quaternion new_q;
00070 new_q.setRPY(0.0f, 0.0f, yaw);
00071 tf2::Transform tf_odom_to_footprint( new_q, new_origin);
00072
00073
00074 tf2::Quaternion q( tf_odom_to_base.transform.rotation.x,
00075 tf_odom_to_base.transform.rotation.y,
00076 tf_odom_to_base.transform.rotation.z,
00077 tf_odom_to_base.transform.rotation.w
00078 );
00079 tf2::Vector3 r( tf_odom_to_base.transform.translation.x,
00080 tf_odom_to_base.transform.translation.y,
00081 tf_odom_to_base.transform.translation.z
00082 );
00083 tf2::Transform tf_odom_to_base_conv( q,r);
00084
00085
00086 tf2::Transform tf_base_to_footprint = tf_odom_to_base_conv.inverse() * tf_odom_to_footprint;
00087
00088
00089 geometry_msgs::TransformStamped message;
00090
00091 message.header.stamp = time;
00092 message.header.frame_id = "base_link";
00093 message.child_frame_id = "base_footprint";
00094
00095 message.transform.rotation.x = tf_base_to_footprint.getRotation().x();
00096 message.transform.rotation.y = tf_base_to_footprint.getRotation().y();
00097 message.transform.rotation.z = tf_base_to_footprint.getRotation().z();
00098 message.transform.rotation.w = tf_base_to_footprint.getRotation().w();
00099 message.transform.translation.x = tf_base_to_footprint.getOrigin().x();
00100 message.transform.translation.y = tf_base_to_footprint.getOrigin().y();
00101 message.transform.translation.z = tf_base_to_footprint.getOrigin().z();
00102
00103
00104
00105
00106 tf2_buffer->setTransform( message, "naoqiconverter", false );
00107 tf_transforms.push_back( message );
00108 }
00109
00110 }
00111 }
00112 }
00113
00114 #endif