transformable_object.h
Go to the documentation of this file.
00001 #ifndef __TRANSFORMABLE_OBJECT_H__
00002 #define __TRANSFORMABLE_OBJECT_H__
00003 
00004 #include <ros/ros.h>
00005 #include <visualization_msgs/Marker.h>
00006 #include <visualization_msgs/InteractiveMarker.h>
00007 #include <visualization_msgs/InteractiveMarkerControl.h>
00008 #include <std_msgs/Float32.h>
00009 #include <std_msgs/ColorRGBA.h>
00010 #include <tf/transform_broadcaster.h>
00011 #include <tf/transform_datatypes.h>
00012 #include <geometry_msgs/Point.h>
00013 #include <jsk_rviz_plugins/RequestMarkerOperate.h>
00014 #include <vector>
00015 #include <algorithm>
00016 #include <jsk_interactive_marker/InteractiveSettingConfig.h>
00017 
00018 namespace jsk_interactive_marker {
00019   class TransformableObject{
00020   public:
00021     TransformableObject();
00022 
00023     std::vector<visualization_msgs::InteractiveMarkerControl> makeRotateTransFixControl(unsigned int orientation_mode = visualization_msgs::InteractiveMarkerControl::FIXED);
00024 
00025     tf::TransformBroadcaster br;
00026     visualization_msgs::InteractiveMarker getInteractiveMarker();
00027     virtual visualization_msgs::Marker getVisualizationMsgMarker(){};
00028     void addMarker(visualization_msgs::InteractiveMarker &int_marker, bool always_visible = true, unsigned int interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_3D);
00029     void addControl(visualization_msgs::InteractiveMarker &int_marker);
00030 
00031     visualization_msgs::Marker marker_;
00032     geometry_msgs::Pose pose_;
00033     geometry_msgs::Pose control_offset_pose_;
00034     std::string name_;
00035     std::string frame_id_;
00036     std::string description_;
00037     int type_;
00038     bool display_interactive_manipulator_;
00039     int interactive_manipulator_orientation_;
00040     
00041     void setPose(geometry_msgs::Pose pose, bool for_interactive_control=false);
00042     void addPose(geometry_msgs::Pose msg, bool relative=false);
00043     void publishTF();
00044     std::string getFrameId() { return frame_id_; }
00045     geometry_msgs::Pose getPose(bool for_interactive_control=false);
00046     void setDisplayInteractiveManipulator(bool v);
00047     void setInteractiveMarkerSetting(InteractiveSettingConfig config);
00048     virtual bool setRadius(std_msgs::Float32 recieve_val){return false;};
00049     virtual bool setSmallRadius(std_msgs::Float32 recieve_val){return false;};
00050     virtual bool setHeight(std_msgs::Float32 recieve_val){return false;};
00051     virtual bool setX(std_msgs::Float32 recieve_val){return false;};
00052     virtual bool setY(std_msgs::Float32 recieve_val){return false;};
00053     virtual bool setZ(std_msgs::Float32 recieve_val){return false;};
00054     virtual void setRGBA(float r , float g, float b, float a){};
00055     virtual void getRGBA(float &r , float &g, float &b, float &a){};
00056     virtual void setXYZ(float x , float y, float z){};
00057     virtual void getXYZ(float &x, float &y, float&z){};
00058     virtual void setRSR(float r , float sr){};
00059     virtual void getRSR(float &r , float &sr){};
00060     virtual void setRZ(float r , float z){};
00061     virtual void getRZ(float &r , float &z){};
00062 
00063     int getType() { return type_; };
00064     void setType(int type) { type_ = type; return; };
00065 
00066     virtual float getInteractiveMarkerScale(){};
00067   };
00068 };
00069 
00070 namespace jsk_interactive_marker
00071 {
00072   class TransformableBox: public TransformableObject
00073   {
00074   public:
00075     TransformableBox( float length , float r, float g, float b, float a, std::string frame, std::string name, std::string description);
00076 
00077     TransformableBox( float x, float y, float z, float r, float g, float b, float a, std::string frame, std::string name, std::string description);
00078 
00079     visualization_msgs::Marker getVisualizationMsgMarker();
00080     void setRGBA( float r , float g, float b, float a){box_r_=r;box_g_=g;box_b_=b;box_a_=a;};
00081     void getRGBA(float &r , float &g, float &b, float &a){r=box_r_;g=box_g_;b=box_b_;a=box_a_;}
00082     void setXYZ( float x , float y, float z){box_x_=x;box_y_=y;box_z_=z;};
00083     void getXYZ(float &x, float &y, float&z){x=box_x_;y=box_y_;z=box_z_;};
00084 
00085     bool setX(std_msgs::Float32 x){box_x_=x.data;return true;};
00086     bool setY(std_msgs::Float32 y){box_y_=y.data;return true;};
00087     bool setZ(std_msgs::Float32 z){box_z_=z.data;return true;};
00088 
00089     float getInteractiveMarkerScale(){return 1+std::max(std::max(box_x_, box_y_),box_z_);};
00090 
00091     float box_x_;
00092     float box_y_;
00093     float box_z_;
00094     float box_r_;
00095     float box_g_;
00096     float box_b_;
00097     float box_a_;
00098   };
00099 };
00100 
00101 namespace jsk_interactive_marker
00102 {
00103   class TransformableMesh: public TransformableObject
00104   {
00105   public:
00106     TransformableMesh(std::string frame, std::string name, std::string description, std::string mesh_resource, bool mesh_use_embedded_materials);
00107     visualization_msgs::Marker getVisualizationMsgMarker();
00108     void setRGBA( float r , float g, float b, float a){mesh_r_=r;mesh_g_=g;mesh_b_=b;mesh_a_=a;};
00109     void getRGBA(float &r , float &g, float &b, float &a){r=mesh_r_;g=mesh_g_;b=mesh_b_;a=mesh_a_;};
00110     void setXYZ( float x , float y, float z){marker_scale_=x; return;};
00111     void getXYZ(float &x, float &y, float&z){return;};
00112     bool setX(std_msgs::Float32 x){marker_scale_=x.data; return true;};
00113     bool setY(std_msgs::Float32 y){return true;};
00114     bool setZ(std_msgs::Float32 z){return true;};
00115     float getInteractiveMarkerScale(){return marker_scale_;};
00116     float marker_scale_;
00117     std::string mesh_resource_;
00118     float mesh_r_;
00119     float mesh_g_;
00120     float mesh_b_;
00121     float mesh_a_;
00122   };
00123 };
00124 
00125 namespace jsk_interactive_marker
00126 {
00127   class TransformableTorus: public TransformableObject
00128   {
00129   public:
00130     TransformableTorus( float radius, float small_radius, int u_div, int v_div, float r, float g, float b, float a, std::string frame, std::string name, std::string description);
00131 
00132     visualization_msgs::Marker getVisualizationMsgMarker();
00133     void setRGBA( float r , float g, float b, float a){torus_r_=r;torus_g_=g;torus_b_=b;torus_a_=a;};
00134     void getRGBA(float &r , float &g, float &b, float &a){r=torus_r_;g=torus_g_;b=torus_b_;a=torus_a_;}
00135     void setRSR( float r , float sr){torus_radius_=r; torus_small_radius_=sr;};
00136     void getRSR(float &r , float &sr){r=torus_radius_; sr=torus_small_radius_;};
00137 
00138     bool setRadius(std_msgs::Float32 r){torus_radius_=r.data;return true;};
00139     bool setSmallRadius(std_msgs::Float32 sr){torus_small_radius_=sr.data;return true;};
00140 
00141     std::vector<geometry_msgs::Point > calcurateTriangleMesh();
00142 
00143     float getInteractiveMarkerScale(){return (torus_radius_+torus_small_radius_+1);};
00144 
00145     float torus_radius_;
00146     float torus_small_radius_;
00147     float torus_r_;
00148     float torus_g_;
00149     float torus_b_;
00150     float torus_a_;
00151 
00152     int u_division_num_;
00153     int v_division_num_;
00154   };
00155 };
00156 
00157 namespace jsk_interactive_marker
00158 {
00159   class TransformableCylinder: public TransformableObject
00160   {
00161   public:
00162     TransformableCylinder( float radius, float z, float r, float g, float b, float a, std::string frame, std::string name, std::string description);
00163 
00164     visualization_msgs::Marker getVisualizationMsgMarker();
00165     void setRGBA( float r , float g, float b, float a){cylinder_r_=r;cylinder_g_=g;cylinder_b_=b;cylinder_a_=a;};
00166     void getRGBA(float &r , float &g, float &b, float &a){r=cylinder_r_;g=cylinder_g_;b=cylinder_b_;a=cylinder_a_;}
00167     void setRZ( float r , float z){cylinder_radius_=r; cylinder_z_=z;};
00168     void getRZ(float &r , float &z){r=cylinder_radius_; z=cylinder_z_;};
00169 
00170     bool setRadius(std_msgs::Float32 r){cylinder_radius_=r.data;return true;};
00171     bool setZ(std_msgs::Float32 z){cylinder_z_=z.data;return true;};
00172 
00173     float getInteractiveMarkerScale(){return 1+std::max(cylinder_radius_, cylinder_z_);};
00174 
00175     float cylinder_radius_;
00176     float cylinder_z_;
00177     float cylinder_r_;
00178     float cylinder_g_;
00179     float cylinder_b_;
00180     float cylinder_a_;
00181   };
00182 };
00183 
00184 #endif


jsk_interactive_marker
Author(s): furuta
autogenerated on Sun Sep 13 2015 22:29:27