32 #ifndef INTERACTIVE_MARKER_SERVER 33 #define INTERACTIVE_MARKER_SERVER 35 #include <visualization_msgs/InteractiveMarkerUpdate.h> 36 #include <visualization_msgs/InteractiveMarkerFeedback.h> 38 #include <boost/scoped_ptr.hpp> 39 #include <boost/thread/thread.hpp> 40 #include <boost/thread/recursive_mutex.hpp> 46 #include <boost/function.hpp> 47 #include <boost/unordered_map.hpp> 72 InteractiveMarkerServer(
const std::string &topic_ns,
const std::string &server_id=
"",
bool spin_thread =
false );
81 void insert(
const visualization_msgs::InteractiveMarker &int_marker );
89 void insert(
const visualization_msgs::InteractiveMarker &int_marker,
90 FeedbackCallback feedback_cb,
91 uint8_t feedback_type=DEFAULT_FEEDBACK_CB );
99 bool setPose(
const std::string &name,
100 const geometry_msgs::Pose &pose,
101 const std_msgs::Header &header=std_msgs::Header() );
107 bool erase(
const std::string &name );
121 std::size_t
size()
const;
133 bool setCallback(
const std::string &name, FeedbackCallback feedback_cb,
134 uint8_t feedback_type=DEFAULT_FEEDBACK_CB );
144 bool get( std::string name, visualization_msgs::InteractiveMarker &int_marker )
const;
186 void publish( visualization_msgs::InteractiveMarkerUpdate &update );
192 void doSetPose( M_UpdateContext::iterator update_it,
193 const std::string &name,
194 const geometry_msgs::Pose &pose,
195 const std_msgs::Header &header );
visualization_msgs::InteractiveMarkerFeedbackConstPtr FeedbackConstPtr
boost::unordered_map< uint8_t, FeedbackCallback > feedback_cbs
ros::Subscriber feedback_sub_
void processFeedback(const FeedbackConstPtr &feedback)
boost::unordered_map< std::string, MarkerContext > M_MarkerContext
visualization_msgs::InteractiveMarker int_marker
boost::function< void(const FeedbackConstPtr &) > FeedbackCallback
M_MarkerContext marker_contexts_
static const uint8_t DEFAULT_FEEDBACK_CB
FeedbackCallback default_feedback_cb
~InteractiveMarkerServer()
Destruction of the interface will lead to all managed markers being cleared.
boost::unordered_map< std::string, UpdateContext > M_UpdateContext
ros::Timer keep_alive_timer_
boost::unordered_map< uint8_t, FeedbackCallback > feedback_cbs
ros::NodeHandle node_handle_
InteractiveMarkerServer(const std::string &topic_ns, const std::string &server_id="", bool spin_thread=false)
visualization_msgs::InteractiveMarker int_marker
volatile bool need_to_terminate_
ros::CallbackQueue callback_queue_
FeedbackCallback default_feedback_cb
void doSetPose(M_UpdateContext::iterator update_it, const std::string &name, const geometry_msgs::Pose &pose, const std_msgs::Header &header)
boost::recursive_mutex mutex_
M_UpdateContext pending_updates_
void insert(const visualization_msgs::InteractiveMarker &int_marker)
void publish(visualization_msgs::InteractiveMarkerUpdate &update)
bool setCallback(const std::string &name, FeedbackCallback feedback_cb, uint8_t feedback_type=DEFAULT_FEEDBACK_CB)
bool setPose(const std::string &name, const geometry_msgs::Pose &pose, const std_msgs::Header &header=std_msgs::Header())
boost::scoped_ptr< boost::thread > spin_thread_
std::string last_client_id
ros::Publisher update_pub_
bool erase(const std::string &name)