$search
00001 00060 // ROS core 00061 #include <ros/ros.h> 00062 #include <tf/transform_listener.h> 00063 #include <tf_conversions/tf_eigen.h> 00064 #include <cob_3d_mapping_msgs/ShapeArray.h> 00065 #include <cob_3d_mapping_common/ros_msg_conversions.h> 00066 00067 00068 using namespace std; 00069 using namespace cob_3d_mapping; 00070 00071 class TransformShapeArray 00072 { 00073 //protected: 00074 // ros::NodeHandle nh_; 00075 00076 public: 00077 string target_frame_; 00078 00079 tf::TransformListener tf_listener_; 00080 ros::Subscriber sub_; 00081 ros::Publisher pub_; 00082 00083 TransformShapeArray() : 00084 target_frame_("/map") 00085 { 00086 ros::NodeHandle private_nh("~"); 00087 pub_ = private_nh.advertise<cob_3d_mapping_msgs::ShapeArray>("output",1); 00088 sub_ = private_nh.subscribe ("input", 1, &TransformShapeArray::cloud_cb, this); 00089 00090 private_nh.getParam ("target_frame", target_frame_); 00091 } 00092 00094 // Callback 00095 void 00096 cloud_cb (const cob_3d_mapping_msgs::ShapeArray::ConstPtr sa_in) 00097 { 00098 if(sa_in->header.frame_id != target_frame_) 00099 { 00100 Eigen::Affine3f af_target = Eigen::Affine3f::Identity(); 00101 tf::StampedTransform trf_map; 00102 00103 try 00104 { 00105 tf_listener_.waitForTransform(target_frame_, sa_in->header.frame_id, sa_in->header.stamp, ros::Duration(2)); 00106 tf_listener_.lookupTransform(target_frame_, sa_in->header.frame_id, sa_in->header.stamp, trf_map); 00107 } 00108 catch (tf::TransformException ex) { ROS_ERROR("[transform shape array] : %s",ex.what()); return; } 00109 00110 Eigen::Affine3d ad; 00111 tf::TransformTFToEigen(trf_map, ad); 00112 af_target = ad.cast<float>(); 00113 cob_3d_mapping_msgs::ShapeArray sa_out; 00114 sa_out.header = sa_in->header; 00115 sa_out.header.frame_id = target_frame_; 00116 for (unsigned int i = 0; i < sa_in->shapes.size (); i++) 00117 { 00118 cob_3d_mapping_msgs::Shape s; 00119 s.header = sa_in->header; 00120 s.header.frame_id = target_frame_; 00121 if( sa_in->shapes[i].type == cob_3d_mapping_msgs::Shape::POLYGON) 00122 { 00123 Polygon::Ptr poly_ptr (new Polygon()); 00124 fromROSMsg(sa_in->shapes[i], *poly_ptr); 00125 poly_ptr->transform2tf(af_target); 00126 toROSMsg(*poly_ptr,s); 00127 } 00128 else if( sa_in->shapes[i].type == cob_3d_mapping_msgs::Shape::CYLINDER) 00129 { 00130 Cylinder::Ptr cyl_ptr (new Cylinder()); 00131 fromROSMsg(sa_in->shapes[i], *cyl_ptr); 00132 cyl_ptr->transform2tf(af_target); 00133 toROSMsg(*cyl_ptr,s); 00134 } 00135 sa_out.shapes.push_back (s); 00136 } 00137 pub_.publish(sa_out); 00138 } 00139 else 00140 pub_.publish(*sa_in); 00141 } 00142 00143 }; 00144 00145 00146 int 00147 main (int argc, char** argv) 00148 { 00149 ros::init (argc, argv, "transform_shape_array"); 00150 00151 TransformShapeArray b; 00152 ros::spin (); 00153 00154 return (0); 00155 } 00156