Go to the documentation of this file.00001 #ifndef __TRANSFORMABLE_CYLINDER_H__
00002 #define __TRANSFORMABLE_CYLINDER_H__
00003
00004
00005 #include <ros/ros.h>
00006 #include <visualization_msgs/Marker.h>
00007 #include <jsk_interactive_marker/transformable_object.h>
00008
00009 namespace jsk_interactive_marker
00010 {
00011 class TransformableCylinder: public TransformableObject
00012 {
00013 public:
00014 TransformableCylinder( float radius, float z, float r, float g, float b, float a, std::string frame, std::string name, std::string description);
00015
00016 visualization_msgs::Marker getVisualizationMsgMarker();
00017 void setRGBA( float r , float g, float b, float a){cylinder_r_=r;cylinder_g_=g;cylinder_b_=b;cylinder_a_=a;};
00018
00019 bool setRadius(std_msgs::Float32 r){cylinder_radius_=r.data;return true;};
00020 bool setZ(std_msgs::Float32 z){cylinder_z_=z.data;return true;};
00021
00022 float getInteractiveMarkerScale(){return 1+std::max(cylinder_radius_, cylinder_z_);};
00023
00024 float cylinder_radius_;
00025 float cylinder_z_;
00026 float cylinder_r_;
00027 float cylinder_g_;
00028 float cylinder_b_;
00029 float cylinder_a_;
00030 };
00031 };
00032
00033 #endif