transformable_interactive_server.h
Go to the documentation of this file.
00001 #ifndef __TRANSFORMABLE_INTERACTIVE_SERVER_H__
00002 #define __TRANSFORMABLE_INTERACTIVE_SERVER_H__
00003 
00004 #include <ros/ros.h>
00005 #include <interactive_markers/interactive_marker_server.h>
00006 #include <jsk_interactive_marker/transformable_box.h>
00007 #include <jsk_interactive_marker/transformable_cylinder.h>
00008 #include <jsk_interactive_marker/transformable_torus.h>
00009 #include <std_msgs/Float32.h>
00010 #include <geometry_msgs/PoseStamped.h>
00011 #include <map>
00012 #include <jsk_rviz_plugins/OverlayText.h>
00013 #include <iostream>
00014 #include <sstream>
00015 
00016 using namespace std;
00017 
00018 namespace jsk_interactive_marker
00019 {
00020   class TransformableInteractiveServer{
00021   public:
00022     TransformableInteractiveServer();
00023     ~TransformableInteractiveServer();
00024 
00025     void processFeedback( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback );
00026     void setRadius(std_msgs::Float32 msg);
00027     void setSmallRadius(std_msgs::Float32 msg);
00028     void setX(std_msgs::Float32 msg);
00029     void setY(std_msgs::Float32 msg);
00030     void setZ(std_msgs::Float32 msg);
00031 
00032     void setPose(geometry_msgs::PoseStamped msg);
00033     void addPose(geometry_msgs::Pose msg);
00034 
00035     void setColor(std_msgs::ColorRGBA msg);
00036 
00037     void insertNewBox( std::string frame_id, std::string name, std::string description );
00038     void insertNewCylinder( std::string frame_id, std::string name, std::string description );
00039     void insertNewTorus( std::string frame_id, std::string name, std::string description );
00040 
00041     void insertNewObject(TransformableObject* tobject, std::string name);
00042 
00043 
00044     void run();
00045     void focusTextPublish();
00046     void focusPosePublish();
00047 
00048     void updateTransformableObject(TransformableObject* tobject);
00049 
00050     bool getPoseService(jsk_interactive_marker::GetPose::Request &req,jsk_interactive_marker::GetPose::Response &res);
00051 
00052     std::string focus_object_marker_name_;
00053     ros::NodeHandle* n_;
00054 
00055     ros::Subscriber setcolor_sub_;
00056     ros::Subscriber setpose_sub_;
00057     ros::Subscriber addpose_sub_;
00058 
00059     ros::Subscriber set_r_sub_;
00060     ros::Subscriber set_sm_r_sub_;
00061     ros::Subscriber set_h_sub_;
00062     ros::Subscriber set_x_sub_;
00063     ros::Subscriber set_y_sub_;
00064     ros::Subscriber set_z_sub_;
00065 
00066     ros::ServiceServer get_pose_srv_;
00067     ros::Subscriber setrad_sub_;
00068     ros::Publisher focus_text_pub_;
00069     ros::Publisher focus_pose_pub_;
00070     interactive_markers::InteractiveMarkerServer* server_;
00071     map<string, TransformableObject*> transformable_objects_map_;
00072 
00073     int torus_udiv_;
00074     int torus_vdiv_;
00075   };
00076 }
00077 
00078 #endif


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