Class InteractiveMarkerServer
Defined in File interactive_marker_server.hpp
Nested Relationships
Nested Types
Class Documentation
-
class interactive_markers::InteractiveMarkerServer
A server to one or many clients (e.g. rviz) displaying a set of interactive markers.
Note that changes made by calling insert(), erase(), setCallback() etc. are not applied until calling applyChanges().
Public Functions
Constructor.
- Parameters
topic_namepsace – The namespace for the ROS services and topics used for communication with interactive marker clients.
base_interface – Node base interface.
clock_interface – Node clock interface.
logging_interface – Node logging interface.
topics_interface – Node topics interface.
service_interface – Node service interface.
update_pub_qos – QoS settings for the update publisher.
feedback_sub_qos – QoS settings for the feedback subscription.
-
template<typename NodePtr>
inline InteractiveMarkerServer(const std::string &topic_namespace, NodePtr node, const rclcpp::QoS &update_pub_qos = rclcpp::QoS(100), const rclcpp::QoS &feedback_sub_qos = rclcpp::QoS(1))
-
INTERACTIVE_MARKERS_PUBLIC ~InteractiveMarkerServer()
Destruction of the interface will lead to all managed markers being cleared.
- INTERACTIVE_MARKERS_PUBLIC void insert (const visualization_msgs::msg::InteractiveMarker &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
marker – The marker to be added or replaced.
- INTERACTIVE_MARKERS_PUBLIC void insert (const visualization_msgs::msg::InteractiveMarker &marker, FeedbackCallback feedback_callback, 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
marker – The marker to be added or replaced.
feedback_callback – Function to call on the arrival of a feedback message.
feedback_type – Type of feedback for which to call the feedback callback.
- INTERACTIVE_MARKERS_PUBLIC bool setPose (const std::string &name, const geometry_msgs::msg::Pose &pose, const std_msgs::msg::Header &header=std_msgs::msg::Header())
Update the pose of a marker by name.
Note, this change will not take effect until you call applyChanges().
- Parameters
name – Name of the interactive marker to update.
pose – The new pose.
header – Header replacement. Leave this empty to use the previous one.
- Returns
true if a marker with the provided name exists, false otherwise.
- INTERACTIVE_MARKERS_PUBLIC bool erase (const std::string &name)
Erase a marker by name.
Note, this change will not take effect until you call applyChanges().
- Parameters
name – Name of the interactive marker to erase.
- Returns
true if a marker with the provided name exists, false otherwise.
- INTERACTIVE_MARKERS_PUBLIC void clear ()
Clear all markers.
Note, this change will not take effect until you call applyChanges().
- INTERACTIVE_MARKERS_PUBLIC bool empty () const
Return whether the server contains any markers.
Does not include markers inserted since the last applyChanges().
- Returns
true if the server contains no markers, false otherwise.
- INTERACTIVE_MARKERS_PUBLIC std::size_t size () const
Return the number of markers contained in the server.
Does not include markers inserted since the last applyChanges().
- Returns
The number of markers contained in the server.
- INTERACTIVE_MARKERS_PUBLIC bool setCallback (const std::string &name, FeedbackCallback feedback_cb, uint8_t feedback_type=DEFAULT_FEEDBACK_CB)
Add or replace a callback function for a 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 an existing interactive marker.
feedback_callback – Function to call on the arrival of a feedback message.
feedback_type – Type of feedback for which to call the feedback callback. Leave this empty to make this the default callback.
- Returns
true if the setting the callback was successful, false if the provided name does not match an existing marker.
- INTERACTIVE_MARKERS_PUBLIC void applyChanges ()
Apply changes made since the last call to this method and broadcast an update to all clients.
- INTERACTIVE_MARKERS_PUBLIC bool get (std::string name, visualization_msgs::msg::InteractiveMarker &int_marker) const
Get a marker by name.
- Parameters
name – [in] Name of the interactive marker.
marker – [out] Output message. Not set if a marker with the provided name does not exist.
- Returns
true if a marker with the provided name exists, false otherwise.
Public Static Attributes
-
static const uint8_t DEFAULT_FEEDBACK_CB = 255