Classes | Public Types | Public Member Functions | Static Public Attributes | Private Types | Private Member Functions | Private Attributes
interactive_markers::InteractiveMarkerServer Class Reference

#include <interactive_marker_server.h>

Inheritance diagram for interactive_markers::InteractiveMarkerServer:
Inheritance graph
[legend]

List of all members.

Classes

struct  MarkerContext
struct  UpdateContext

Public Types

typedef boost::function< void(const
FeedbackConstPtr &) > 
FeedbackCallback
typedef
visualization_msgs::InteractiveMarkerFeedbackConstPtr 
FeedbackConstPtr

Public Member Functions

void applyChanges ()
void clear ()
bool erase (const std::string &name)
bool get (std::string name, visualization_msgs::InteractiveMarker &int_marker) const
void insert (const visualization_msgs::InteractiveMarker &int_marker)
void insert (const visualization_msgs::InteractiveMarker &int_marker, FeedbackCallback feedback_cb, uint8_t feedback_type=DEFAULT_FEEDBACK_CB)
 InteractiveMarkerServer (const std::string &topic_ns, const std::string &server_id="", bool spin_thread=false)
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())
 ~InteractiveMarkerServer ()
 Destruction of the interface will lead to all managed markers being cleared.

Static Public Attributes

static const uint8_t DEFAULT_FEEDBACK_CB = 255

Private Types

typedef boost::unordered_map
< std::string, MarkerContext
M_MarkerContext
typedef boost::unordered_map
< std::string, UpdateContext
M_UpdateContext

Private Member Functions

void doSetPose (M_UpdateContext::iterator update_it, const std::string &name, const geometry_msgs::Pose &pose, const std_msgs::Header &header)
void keepAlive ()
void processFeedback (const FeedbackConstPtr &feedback)
void publish (visualization_msgs::InteractiveMarkerUpdate &update)
void publishInit ()
void spinThread ()

Private Attributes

ros::CallbackQueue callback_queue_
ros::Subscriber feedback_sub_
ros::Publisher init_pub_
ros::Timer keep_alive_timer_
M_MarkerContext marker_contexts_
boost::recursive_mutex mutex_
volatile bool need_to_terminate_
ros::NodeHandle node_handle_
M_UpdateContext pending_updates_
uint64_t seq_num_
std::string server_id_
boost::scoped_ptr< boost::thread > spin_thread_
std::string topic_ns_
ros::Publisher update_pub_

Detailed Description

Acts as a server to one or many GUIs (e.g. rviz) displaying a set of interactive markers

Note: Keep in mind that changes made by calling insert(), erase(), setCallback() etc. are not applied until calling applyChanges().

Definition at line 56 of file interactive_marker_server.h.


Member Typedef Documentation

Definition at line 61 of file interactive_marker_server.h.

typedef visualization_msgs::InteractiveMarkerFeedbackConstPtr interactive_markers::InteractiveMarkerServer::FeedbackConstPtr

Definition at line 60 of file interactive_marker_server.h.

typedef boost::unordered_map< std::string, MarkerContext > interactive_markers::InteractiveMarkerServer::M_MarkerContext [private]

Definition at line 147 of file interactive_marker_server.h.

typedef boost::unordered_map< std::string, UpdateContext > interactive_markers::InteractiveMarkerServer::M_UpdateContext [private]

Definition at line 162 of file interactive_marker_server.h.


Constructor & Destructor Documentation

interactive_markers::InteractiveMarkerServer::InteractiveMarkerServer ( const std::string &  topic_ns,
const std::string &  server_id = "",
bool  spin_thread = false 
)
Parameters:
topic_nsThe interface will use the topics topic_ns/update and topic_ns/feedback for communication.
server_idIf you run multiple servers on the same topic from within the same node, you will need to assign different names to them. Otherwise, leave this empty.
spin_threadIf set to true, will spin up a thread for message handling. All callbacks will be called from that thread.

Definition at line 42 of file interactive_marker_server.cpp.

Destruction of the interface will lead to all managed markers being cleared.

Definition at line 81 of file interactive_marker_server.cpp.


Member Function Documentation

Apply changes made since the last call to this method & broadcast an update to all clients.

Definition at line 110 of file interactive_marker_server.cpp.

Clear all markers. Note: This change will not take effect until you call applyChanges().

Definition at line 199 of file interactive_marker_server.cpp.

void interactive_markers::InteractiveMarkerServer::doSetPose ( M_UpdateContext::iterator  update_it,
const std::string &  name,
const geometry_msgs::Pose pose,
const std_msgs::Header header 
) [private]

Definition at line 445 of file interactive_marker_server.cpp.

Erase the marker with the specified name Note: This change will not take effect until you call applyChanges().

Returns:
true if a marker with that name exists
Parameters:
nameName of the interactive marker

Definition at line 191 of file interactive_marker_server.cpp.

bool interactive_markers::InteractiveMarkerServer::get ( std::string  name,
visualization_msgs::InteractiveMarker &  int_marker 
) const

Get marker by name

Parameters:
nameName of the interactive marker
[out]int_markerOutput message
Returns:
true if a marker with that name exists

Definition at line 315 of file interactive_marker_server.cpp.

void interactive_markers::InteractiveMarkerServer::insert ( const visualization_msgs::InteractiveMarker &  int_marker)

Add or replace a marker without changing its callback functions. Note: Changes to the marker will not take effect until you call applyChanges(). The callback changes immediately.

Parameters:
int_markerThe marker to be added or replaced

Definition at line 293 of file interactive_marker_server.cpp.

void interactive_markers::InteractiveMarkerServer::insert ( const visualization_msgs::InteractiveMarker &  int_marker,
FeedbackCallback  feedback_cb,
uint8_t  feedback_type = DEFAULT_FEEDBACK_CB 
)

Add or replace a marker and its callback functions Note: Changes to the marker will not take effect until you call applyChanges(). The callback changes immediately.

Parameters:
int_markerThe marker to be added or replaced
feedback_cbFunction to call on the arrival of a feedback message.
feedback_typeType of feedback for which to call the feedback.

Definition at line 307 of file interactive_marker_server.cpp.

Definition at line 429 of file interactive_marker_server.cpp.

Definition at line 376 of file interactive_marker_server.cpp.

void interactive_markers::InteractiveMarkerServer::publish ( visualization_msgs::InteractiveMarkerUpdate &  update) [private]

Definition at line 437 of file interactive_marker_server.cpp.

Definition at line 357 of file interactive_marker_server.cpp.

bool interactive_markers::InteractiveMarkerServer::setCallback ( const std::string &  name,
FeedbackCallback  feedback_cb,
uint8_t  feedback_type = DEFAULT_FEEDBACK_CB 
)

Add or replace a callback function for the specified marker. Note: This change will not take effect until you call applyChanges(). The server will try to call any type-specific callback first. If none is set, it will call the default callback. If a callback for the given type already exists, it will be replaced. To unset a type-specific callback, pass in an empty one.

Parameters:
nameName of the interactive marker
feedback_cbFunction to call on the arrival of a feedback message.
feedback_typeType of feedback for which to call the feedback. Leave this empty to make this the default callback.

Definition at line 237 of file interactive_marker_server.cpp.

bool interactive_markers::InteractiveMarkerServer::setPose ( const std::string &  name,
const geometry_msgs::Pose pose,
const std_msgs::Header header = std_msgs::Header() 
)

Update the pose of a marker with the specified name Note: This change will not take effect until you call applyChanges()

Returns:
true if a marker with that name exists
Parameters:
nameName of the interactive marker
poseThe new pose
headerHeader replacement. Leave this empty to use the previous one.

Definition at line 211 of file interactive_marker_server.cpp.

Definition at line 97 of file interactive_marker_server.cpp.


Member Data Documentation

Definition at line 201 of file interactive_marker_server.h.

Definition at line 63 of file interactive_marker_server.h.

Definition at line 209 of file interactive_marker_server.h.

Definition at line 207 of file interactive_marker_server.h.

Definition at line 205 of file interactive_marker_server.h.

Definition at line 188 of file interactive_marker_server.h.

boost::recursive_mutex interactive_markers::InteractiveMarkerServer::mutex_ [private]

Definition at line 196 of file interactive_marker_server.h.

Definition at line 202 of file interactive_marker_server.h.

Definition at line 200 of file interactive_marker_server.h.

Definition at line 191 of file interactive_marker_server.h.

Definition at line 211 of file interactive_marker_server.h.

Definition at line 213 of file interactive_marker_server.h.

boost::scoped_ptr<boost::thread> interactive_markers::InteractiveMarkerServer::spin_thread_ [private]

Definition at line 199 of file interactive_marker_server.h.

Definition at line 194 of file interactive_marker_server.h.

Definition at line 208 of file interactive_marker_server.h.


The documentation for this class was generated from the following files:


interactive_markers
Author(s): David Gossow (C++), Michael Ferguson (Python)
autogenerated on Mon Jan 6 2014 11:54:25