#include <interactive_marker_server.h>
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.
interactive_markers::InteractiveMarkerServer::InteractiveMarkerServer |
( |
const std::string & |
topic_ns, |
|
|
const std::string & |
server_id = "" , |
|
|
bool |
spin_thread = false |
|
) |
| |
- Parameters
-
topic_ns | The interface will use the topics topic_ns/update and topic_ns/feedback for communication. |
server_id | If 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_thread | If 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.
interactive_markers::InteractiveMarkerServer::~InteractiveMarkerServer |
( |
| ) |
|
void interactive_markers::InteractiveMarkerServer::applyChanges |
( |
| ) |
|
void interactive_markers::InteractiveMarkerServer::clear |
( |
| ) |
|
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 |
bool interactive_markers::InteractiveMarkerServer::empty |
( |
| ) |
const |
bool interactive_markers::InteractiveMarkerServer::erase |
( |
const std::string & |
name | ) |
|
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
-
name | Name of the interactive marker |
Definition at line 192 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
-
| name | Name of the interactive marker |
[out] | int_marker | Output message |
- Returns
- true if a marker with that name exists
Definition at line 342 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_marker | The marker to be added or replaced |
Definition at line 320 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_marker | The marker to be added or replaced |
feedback_cb | Function to call on the arrival of a feedback message. |
feedback_type | Type of feedback for which to call the feedback. |
Definition at line 334 of file interactive_marker_server.cpp.
void interactive_markers::InteractiveMarkerServer::keepAlive |
( |
| ) |
|
|
private |
void interactive_markers::InteractiveMarkerServer::processFeedback |
( |
const FeedbackConstPtr & |
feedback | ) |
|
|
private |
void interactive_markers::InteractiveMarkerServer::publish |
( |
visualization_msgs::InteractiveMarkerUpdate & |
update | ) |
|
|
private |
void interactive_markers::InteractiveMarkerServer::publishInit |
( |
| ) |
|
|
private |
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
-
name | Name of the interactive marker |
feedback_cb | Function to call on the arrival of a feedback message. |
feedback_type | Type of feedback for which to call the feedback. Leave this empty to make this the default callback. |
Definition at line 264 of file interactive_marker_server.cpp.
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
-
name | Name of the interactive marker |
pose | The new pose |
header | Header replacement. Leave this empty to use the previous one. |
Definition at line 226 of file interactive_marker_server.cpp.
std::size_t interactive_markers::InteractiveMarkerServer::size |
( |
| ) |
const |
Return the number of markers contained in the server Note: Does not include markers inserted since the last applyChanges().
- Returns
- The number of markers contained in the server
Definition at line 220 of file interactive_marker_server.cpp.
void interactive_markers::InteractiveMarkerServer::spinThread |
( |
| ) |
|
|
private |
const uint8_t interactive_markers::InteractiveMarkerServer::DEFAULT_FEEDBACK_CB = 255 |
|
static |
ros::Subscriber interactive_markers::InteractiveMarkerServer::feedback_sub_ |
|
private |
ros::Publisher interactive_markers::InteractiveMarkerServer::init_pub_ |
|
private |
ros::Timer interactive_markers::InteractiveMarkerServer::keep_alive_timer_ |
|
private |
M_MarkerContext interactive_markers::InteractiveMarkerServer::marker_contexts_ |
|
private |
boost::recursive_mutex interactive_markers::InteractiveMarkerServer::mutex_ |
|
mutableprivate |
volatile bool interactive_markers::InteractiveMarkerServer::need_to_terminate_ |
|
private |
M_UpdateContext interactive_markers::InteractiveMarkerServer::pending_updates_ |
|
private |
uint64_t interactive_markers::InteractiveMarkerServer::seq_num_ |
|
private |
std::string interactive_markers::InteractiveMarkerServer::server_id_ |
|
private |
boost::scoped_ptr<boost::thread> interactive_markers::InteractiveMarkerServer::spin_thread_ |
|
private |
std::string interactive_markers::InteractiveMarkerServer::topic_ns_ |
|
private |
ros::Publisher interactive_markers::InteractiveMarkerServer::update_pub_ |
|
private |
The documentation for this class was generated from the following files: