00001 /* 00002 * M3 Component to abstract PDO over serial (rather than ethercat) 00003 * Copyright (C) 2011 Meka Robotics 00004 * Author: Pierre-Luc Bacon <pierrelucbacon@mekabot.com> 00005 * 00006 * This program is free software; you can redistribute it and/or 00007 * modify it under the terms of the GNU General Public License 00008 * as published by the Free Software Foundation; either version 2 00009 * of the License, or (at your option) any later version. 00010 * 00011 * This program is distributed in the hope that it will be useful, 00012 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00013 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00014 * GNU General Public License for more details. 00015 * 00016 * You should have received a copy of the GNU General Public License 00017 * along with this program; if not, write to the Free Software 00018 * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, USA. 00019 */ 00020 00021 #ifndef ROSTAXELSTRANSFORMNODE_H_ 00022 #define ROSTAXELSTRANSFORMNODE_H_ 00023 00024 #include <m3skin_ros/RawTaxelArray.h> 00025 #include <m3skin_ros/TaxelArray.h> 00026 00027 #include <ros/ros.h> 00028 #include <geometry_msgs/Transform.h> 00029 00030 #include <tf/transform_broadcaster.h> 00031 00032 namespace m3 { 00033 00034 class RosTaxelsTransformNode { 00035 public: 00036 RosTaxelsTransformNode(); 00037 virtual ~RosTaxelsTransformNode(); 00038 00044 void Init(unsigned calibration_samples = 0); 00045 00053 void SetCalibrateMode(bool on); 00054 00058 bool IsCalibrateMode(); 00059 00060 static const double MAX_VALUE = 30; 00061 00062 protected: 00067 void TransformMessage(const m3skin_ros::RawTaxelArray::ConstPtr& msg); 00068 00074 virtual m3skin_ros::RawTaxelArray FilterRaw(const m3skin_ros::RawTaxelArray::ConstPtr& msg); 00075 00081 void GetTaxelTransforms(); 00082 00087 void GetLinkName(); 00088 00094 tf::Transform GeometryTransformToTf(geometry_msgs::Transform& gtf); 00095 00100 void CalibrateBias(std::vector<int> values); 00101 00102 private: 00103 00107 void InitStaticVectors(); 00108 00113 double GetUnbiased(unsigned value, unsigned index); 00114 00115 ros::NodeHandle n; 00116 ros::Publisher publisher; 00117 ros::Subscriber subscriber; 00118 ros::ServiceClient local_coords_client; 00119 ros::ServiceClient link_name_client; 00120 00121 std::vector<geometry_msgs::Transform> transforms; 00122 std::vector<tf::Transform> fullTfs; 00123 00124 std::vector<tf::Vector3> centers; 00125 std::vector<tf::Vector3> normals; 00126 00127 std::vector<double> biases; 00128 unsigned number_samples; 00129 unsigned number_samples_target; 00130 bool calibrating; 00131 00132 std::string linkName; 00133 00134 static const unsigned number_taxels = 384; // TODO Get this value from the server 00135 }; 00136 00137 } 00138 00139 #endif /* ROSTAXELSTRANSFORMNODE_H_ */