Public Member Functions | Protected Member Functions | Static Protected Attributes | Private Member Functions | Private Attributes
m3::RosPressureVisualizer Class Reference

#include <RosPressureVisualizer.h>

List of all members.

Public Member Functions

void Init ()
 RosPressureVisualizer ()
virtual ~RosPressureVisualizer ()

Protected Member Functions

void DisplayPressure (const hrl_haptic_manipulation_in_clutter_msgs::TaxelArray::ConstPtr &msg)
visualization_msgs::Marker GetArrowMarker (tf::Vector3 position, tf::Quaternion orientation, double scale)
void GetArrowTextMarkers (tf::Vector3 position, tf::Quaternion orientation, double scale, visualization_msgs::Marker *arrow, visualization_msgs::Marker *text, double nx, double ny, double nz)
void GetLinkName ()
void GetTaxelTransforms ()
double norm (double x, double y, double z)

Static Protected Attributes

static const double DURATION_ARROW = 0.1
static const unsigned FREQUENCY_DIVISOR = 2
static const double MIN_PRESSURE_VALUE = 0.2
static const double SCALE_ARROW_Y = 0.25
static const double SCALE_ARROW_Z = 0.25
static const double SCALING_FACTOR = 0.05
static const double TF_TIME_OFFSET = 0.200

Private Member Functions

void InitStaticVectors ()

Private Attributes

unsigned frequency_count
ros::ServiceClient link_name_client
std::string linkName
ros::ServiceClient local_coords_client
ros::NodeHandle n
ros::Publisher publisher_marker
ros::Publisher publisher_marker_array
ros::Publisher publisher_text_marker
ros::Publisher publisher_text_marker_array
ros::Subscriber subscriber
std::vector< tf::Quaterniontaxels_arrows_quaternions
std::vector< tf::Transformtaxels_transforms
std::vector< tf::Transformtaxels_transforms_inv
std::vector
< geometry_msgs::Transform > 
transforms

Detailed Description

Definition at line 41 of file RosPressureVisualizer.h.


Constructor & Destructor Documentation

Definition at line 241 of file RosPressureVisualizer.cpp.

Definition at line 245 of file RosPressureVisualizer.cpp.


Member Function Documentation

Publishes a TaxelArray message from the RawTaxelArray message

Parameters:
msgThe RawTaxeArray message to transform

Definition at line 126 of file RosPressureVisualizer.cpp.

visualization_msgs::Marker m3::RosPressureVisualizer::GetArrowMarker ( tf::Vector3  position,
tf::Quaternion  orientation,
double  scale 
) [protected]

Definition at line 31 of file RosPressureVisualizer.cpp.

void m3::RosPressureVisualizer::GetArrowTextMarkers ( tf::Vector3  position,
tf::Quaternion  orientation,
double  scale,
visualization_msgs::Marker *  arrow,
visualization_msgs::Marker *  text,
double  nx,
double  ny,
double  nz 
) [protected]

Definition at line 60 of file RosPressureVisualizer.cpp.

Fetches the link name The link name will be stored inside this object.

Definition at line 200 of file RosPressureVisualizer.cpp.

Fetches all the taxels tfs from the /skin_patch_forearm_right/taxels/srv/local_coord_frames service The transforms will be stored inside this object.

Definition at line 178 of file RosPressureVisualizer.cpp.

Definition at line 212 of file RosPressureVisualizer.cpp.

Initialize the centers and normals vectors

double m3::RosPressureVisualizer::norm ( double  x,
double  y,
double  z 
) [inline, protected]

Compute the norm

Definition at line 86 of file RosPressureVisualizer.h.


Member Data Documentation

const double m3::RosPressureVisualizer::DURATION_ARROW = 0.1 [static, protected]

Definition at line 70 of file RosPressureVisualizer.h.

Definition at line 119 of file RosPressureVisualizer.h.

const unsigned m3::RosPressureVisualizer::FREQUENCY_DIVISOR = 2 [static, protected]

Definition at line 75 of file RosPressureVisualizer.h.

Definition at line 110 of file RosPressureVisualizer.h.

std::string m3::RosPressureVisualizer::linkName [private]

Definition at line 117 of file RosPressureVisualizer.h.

Definition at line 109 of file RosPressureVisualizer.h.

const double m3::RosPressureVisualizer::MIN_PRESSURE_VALUE = 0.2 [static, protected]

Definition at line 71 of file RosPressureVisualizer.h.

Definition at line 103 of file RosPressureVisualizer.h.

Definition at line 106 of file RosPressureVisualizer.h.

Definition at line 107 of file RosPressureVisualizer.h.

Definition at line 104 of file RosPressureVisualizer.h.

Definition at line 105 of file RosPressureVisualizer.h.

const double m3::RosPressureVisualizer::SCALE_ARROW_Y = 0.25 [static, protected]

Definition at line 68 of file RosPressureVisualizer.h.

const double m3::RosPressureVisualizer::SCALE_ARROW_Z = 0.25 [static, protected]

Definition at line 69 of file RosPressureVisualizer.h.

const double m3::RosPressureVisualizer::SCALING_FACTOR = 0.05 [static, protected]

Definition at line 72 of file RosPressureVisualizer.h.

Definition at line 108 of file RosPressureVisualizer.h.

Definition at line 115 of file RosPressureVisualizer.h.

Definition at line 113 of file RosPressureVisualizer.h.

Definition at line 114 of file RosPressureVisualizer.h.

const double m3::RosPressureVisualizer::TF_TIME_OFFSET = 0.200 [static, protected]

Definition at line 80 of file RosPressureVisualizer.h.

std::vector<geometry_msgs::Transform> m3::RosPressureVisualizer::transforms [private]

Definition at line 112 of file RosPressureVisualizer.h.


The documentation for this class was generated from the following files:


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