RosPressureVisualizer.h
Go to the documentation of this file.
00001 /*
00002  * Sends markers to RViz to visualize the pressure
00003  * being applied on a taxel array sensor.
00004  *
00005  * Copyright (C) 2011  Meka Robotics
00006  * Author: Pierre-Luc Bacon <pierrelucbacon@mekabot.com>
00007  *
00008  * This program is free software; you can redistribute it and/or
00009  * modify it under the terms of the GNU General Public License
00010  * as published by the Free Software Foundation; either version 2
00011  * of the License, or (at your option) any later version.
00012  *
00013  * This program is distributed in the hope that it will be useful,
00014  * but WITHOUT ANY WARRANTY; without even the implied warranty of
00015  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00016  * GNU General Public License for more details.
00017  *
00018  * You should have received a copy of the GNU General Public License
00019  * along with this program; if not, write to the Free Software
00020  * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301, USA.
00021  */
00022 
00023 #ifndef RosPressureVisualizer_H_
00024 #define RosPressureVisualizer_H_
00025 
00026 #include <m3skin_ros/RawTaxelArray.h>
00027 #include <hrl_haptic_manipulation_in_clutter_msgs/TaxelArray.h>
00028 //#include <m3skin_ros/TaxelArray.h>
00029 
00030 #include <math.h>
00031 
00032 #include <ros/ros.h>
00033 #include <geometry_msgs/Transform.h>
00034 #include <tf/transform_broadcaster.h>
00035 #include <tf/transform_datatypes.h>
00036 #include <visualization_msgs/Marker.h>
00037 
00038 
00039 namespace m3 {
00040 
00041 class RosPressureVisualizer {
00042 public:
00043         RosPressureVisualizer();
00044         virtual ~RosPressureVisualizer();
00045         void Init();
00046 
00047 protected:
00052         void DisplayPressure(const hrl_haptic_manipulation_in_clutter_msgs::TaxelArray::ConstPtr& msg);
00053 
00059         void GetTaxelTransforms();
00060 
00065         void GetLinkName();
00066 
00067 
00068         static const double SCALE_ARROW_Y = 0.25;
00069         static const double SCALE_ARROW_Z = 0.25;
00070         static const double DURATION_ARROW = 0.1;
00071         static const double MIN_PRESSURE_VALUE = 0.2;
00072         static const double SCALING_FACTOR = 0.05;
00073 
00074         // It is good enough for us if the visualization runs at around 50Hz
00075         static const unsigned FREQUENCY_DIVISOR = 2;
00076 
00077         // Setting a larger value would request an older tf in the tf buffer
00078         // used by RViz. That way, we avoid errors from RViz, and this one does
00079         // not wait on a most recent transform to arrive. In ms.
00080         static const double TF_TIME_OFFSET = 0.200;
00081 
00082 protected:
00086         inline double norm(double x, double y, double z) {
00087         return sqrt(x*x+y*y+z*z);
00088         }
00089 
00090         visualization_msgs::Marker GetArrowMarker(tf::Vector3 position, tf::Quaternion orientation, double scale);
00091     void GetArrowTextMarkers(tf::Vector3 position, tf::Quaternion orientation,
00092                              double scale, visualization_msgs::Marker *arrow,
00093                              visualization_msgs::Marker *text,
00094                              double nx, double ny, double nz);
00095 
00096 private:
00097 
00101         void InitStaticVectors();
00102 
00103         ros::NodeHandle n;
00104         ros::Publisher publisher_text_marker;
00105         ros::Publisher publisher_text_marker_array;
00106         ros::Publisher publisher_marker;
00107         ros::Publisher publisher_marker_array;
00108         ros::Subscriber subscriber;
00109         ros::ServiceClient local_coords_client;
00110         ros::ServiceClient link_name_client;
00111 
00112         std::vector<geometry_msgs::Transform> transforms;
00113         std::vector<tf::Transform> taxels_transforms;
00114         std::vector<tf::Transform> taxels_transforms_inv;
00115         std::vector<tf::Quaternion> taxels_arrows_quaternions;
00116 
00117         std::string linkName;
00118 
00119         unsigned frequency_count;
00120 };
00121 
00122 }
00123 
00124 #endif /* RosPressureVisualizer_H_ */


m3skin_viz
Author(s): Meka Robotics
autogenerated on Wed Nov 27 2013 11:35:59