transformable_box.h
Go to the documentation of this file.
00001 #ifndef __TRANSFORMABLE_BOX_H__
00002 #define __TRANSFORMABLE_BOX_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 TransformableBox: public TransformableObject
00012   {
00013   public:
00014     TransformableBox( float length , float r, float g, float b, float a, std::string frame, std::string name, std::string description);
00015 
00016     TransformableBox( float x, float y, float z, float r, float g, float b, float a, std::string frame, std::string name, std::string description);
00017 
00018     visualization_msgs::Marker getVisualizationMsgMarker();
00019     void setXYZ( float x , float y, float z){box_x_=x;box_y_=y;box_z_=z;};
00020     void setRGBA( float r , float g, float b, float a){box_r_=r;box_g_=g;box_b_=b;box_a_=a;};
00021 
00022     bool setX(std_msgs::Float32 x){box_x_=x.data;return true;};
00023     bool setY(std_msgs::Float32 y){box_y_=y.data;return true;};
00024     bool setZ(std_msgs::Float32 z){box_z_=z.data;return true;};
00025 
00026     float getInteractiveMarkerScale(){return 1+std::max(std::max(box_x_, box_y_),box_z_);};
00027 
00028     float box_x_;
00029     float box_y_;
00030     float box_z_;
00031     float box_r_;
00032     float box_g_;
00033     float box_b_;
00034     float box_a_;
00035   };
00036 };
00037 
00038 #endif


jsk_interactive_marker
Author(s): furuta
autogenerated on Mon Oct 6 2014 01:19:15