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 <geometry_msgs/Point.h>
00010 #include <jsk_interactive_marker/GetPose.h>
00011 #include <vector>
00012 #include <algorithm>
00013 
00014 namespace jsk_interactive_marker {
00015   class TransformableObject{
00016   public:
00017     TransformableObject();
00018 
00019     std::vector<visualization_msgs::InteractiveMarkerControl> makeRotateTransFixControl();
00020 
00021     visualization_msgs::InteractiveMarker getInteractiveMarker();
00022     virtual visualization_msgs::Marker getVisualizationMsgMarker(){};
00023     void addMarker(visualization_msgs::InteractiveMarker &int_marker, bool always_visible = true, unsigned int interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_3D);
00024     void addControl(visualization_msgs::InteractiveMarker &int_marker, bool fixed = true);
00025 
00026     visualization_msgs::Marker marker_;
00027     geometry_msgs::Pose pose_;
00028     std::string name_;
00029     std::string frame_id_;
00030     std::string description_;
00031 
00032     void setPose(geometry_msgs::Pose pose){pose_=pose;};
00033     void addPose(geometry_msgs::Pose msg);
00034     geometry_msgs::Pose getPose(){return pose_;};
00035     virtual bool setRadius(std_msgs::Float32 recieve_val){return false;};
00036     virtual bool setSmallRadius(std_msgs::Float32 recieve_val){return false;};
00037     virtual bool setHeight(std_msgs::Float32 recieve_val){return false;};
00038     virtual bool setX(std_msgs::Float32 recieve_val){return false;};
00039     virtual bool setY(std_msgs::Float32 recieve_val){return false;};
00040     virtual bool setZ(std_msgs::Float32 recieve_val){return false;};
00041     virtual void setRGBA(float r , float g, float b, float a){};
00042 
00043     virtual float getInteractiveMarkerScale(){};
00044   };
00045 };
00046 
00047 #endif


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