Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 #ifndef MOVEIT_ROBOT_INTERACTION_INTERACTIVE_MARKER_HELPERS_
00031 #define MOVEIT_ROBOT_INTERACTION_INTERACTIVE_MARKER_HELPERS_
00032 
00033 #include <visualization_msgs/InteractiveMarker.h>
00034 #include <geometry_msgs/PoseStamped.h>
00035 #include <std_msgs/ColorRGBA.h>
00036 
00037 namespace robot_interaction
00038 {
00039 
00040 visualization_msgs::InteractiveMarker makeEmptyInteractiveMarker(const std::string& name,
00041                                                      const geometry_msgs::PoseStamped &stamped,
00042                                                      double scale);
00043 
00044 visualization_msgs::InteractiveMarker make6DOFMarker(const std::string& name,
00045                                                      const geometry_msgs::PoseStamped &stamped,
00046                                                      double scale,
00047                                                      bool orientation_fixed = false);
00048 
00049 visualization_msgs::InteractiveMarker makePlanarXYMarker(const std::string& name,
00050                                                      const geometry_msgs::PoseStamped &stamped,
00051                                                      double scale,
00052                                                      bool orientation_fixed = false);
00053 
00054 void addTArrowMarker(visualization_msgs::InteractiveMarker &im);
00055 
00056 void addErrorMarker(visualization_msgs::InteractiveMarker &im);
00057 
00058 void add6DOFControl(visualization_msgs::InteractiveMarker& int_marker, bool orientation_fixed = false);
00059 
00060 void addPlanarXYControl(visualization_msgs::InteractiveMarker& int_marker, bool orientation_fixed = false);
00061 
00062 void addOrientationControl(visualization_msgs::InteractiveMarker& int_marker, bool orientation_fixed = false);
00063 
00064 void addPositionControl(visualization_msgs::InteractiveMarker& int_marker, bool orientation_fixed = false);
00065 
00066 void addViewPlaneControl(visualization_msgs::InteractiveMarker& int_marker, double radius, const std_msgs::ColorRGBA& color, bool position = true, bool orientation = true);
00067 
00068 }
00069 
00070 #endif