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
00031
00032
00033 #ifndef _GRASP_MARKER_PUBLISHER_H_
00034 #define _GRASP_MARKER_PUBLISHER_H_
00035
00036 #include <string>
00037 #include <boost/thread/thread.hpp>
00038 #include <boost/thread/mutex.hpp>
00039
00040 #include <ros/ros.h>
00041
00042 #include <visualization_msgs/Marker.h>
00043
00044 #include <geometry_msgs/PoseStamped.h>
00045
00046 namespace object_manipulator {
00047
00049 class GraspMarkerPublisher
00050 {
00051 private:
00053 ros::NodeHandle priv_nh_;
00054
00056 ros::Publisher marker_pub_;
00057
00059 std::vector<visualization_msgs::Marker> grasp_markers_;
00060
00062 std::string ns_append_;
00063
00065 boost::thread *publishing_thread_;
00066
00068 boost::mutex mutex_;
00069
00071 double continuous_publishing_rate_;
00072
00074 void publishingThread();
00075
00077 void init(std::string marker_out_name, std::string ns_append, double publishing_rate);
00078
00079 public:
00081 GraspMarkerPublisher();
00082
00084 GraspMarkerPublisher(std::string marker_out_name, std::string ns_append, double publishing_rate);
00085
00087 ~GraspMarkerPublisher();
00088
00090 void clearAllMarkers();
00091
00093 unsigned int addGraspMarker(const geometry_msgs::PoseStamped &marker_pose);
00094
00096 void setNamespaceSuffix(std::string ns_append) { ns_append_ = ns_append; }
00097
00099 void colorGraspMarker(unsigned int marker_id, float r, float g, float b);
00100
00102 void setMarkerPose(unsigned int marker_id, const geometry_msgs::PoseStamped &marker_pose);
00103 };
00104
00105
00106
00107 }
00108
00109 #endif