Class InteractiveMarkerClient

Class Documentation

class InteractiveMarkerClient

Acts as a client to one or multiple Interactive Marker servers.

Handles topic subscription, error detection and tf transformations.

After connecting to a provided namespace, the client sends a service request to an available interactive marker server to get an initial set of markers. Once initialized, feedback messages may be sent from the client to the server as well as update messages received from the server.

In case of an error (e.g. update message loss or tf failure), the connection to the server is reset.

All timestamped messages are being transformed into the target frame, while for non-timestamped messages it is ensured that the necessary tf transformation will be available.

Public Types

enum Status

Values:

enumerator STATUS_DEBUG
enumerator STATUS_INFO
enumerator STATUS_WARN
enumerator STATUS_ERROR
enum State

Values:

enumerator STATE_IDLE
enumerator STATE_INITIALIZE
enumerator STATE_RUNNING
typedef std::function<void(visualization_msgs::msg::InteractiveMarkerUpdate::SharedPtr)> UpdateCallback
typedef std::function<void(visualization_msgs::srv::GetInteractiveMarkers::Response::SharedPtr)> InitializeCallback
typedef std::function<void()> ResetCallback
typedef std::function<void(const Status, const std::string&)> StatusCallback

Public Functions

template<class Rep = int64_t, class Period = std::ratio<1>>
inline InteractiveMarkerClient(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface, rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr topics_interface, rclcpp::node_interfaces::NodeServicesInterface::SharedPtr services_interface, rclcpp::node_interfaces::NodeGraphInterface::SharedPtr graph_interface, rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface, rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr logging_interface, std::shared_ptr<tf2::BufferCoreInterface> tf_buffer_core, const std::string &target_frame = "", const std::string &topic_namespace = "", const std::chrono::duration<Rep, Period> &request_timeout = std::chrono::seconds(1), const rclcpp::QoS &update_sub_qos = rclcpp::QoS(100), const rclcpp::QoS &feedback_pub_qos = rclcpp::QoS(100))

Constructor.

Parameters:
  • node_base_interface – The node base interface for creating the service client.

  • topics_interface – The node topics interface for creating publishers and subscriptions.

  • graph_interface – The node graph interface for querying the ROS graph.

  • clock_interface – The node clock interface for getting the current time.

  • logging_interface – The node logging interface for logging messages.

  • tf_buffer_core – The tf transformer to use.

  • target_frame – The tf frame to transform timestamped messages into.

  • topic_namespace – The interactive marker topic namespace. This is the namespace used for the underlying ROS service and topics for communication between the client and server. If the namespace is not empty, then connect() is called.

  • request_timeout – Timeout in seconds before retrying to request interactive markers from a connected server.

  • update_sub_qos – QoS settings for the underlying update subscription.

  • feedback_pub_qos – QoS settings for the underlying feedback publisher.

template<typename NodePtr, class Rep = int64_t, class Period = std::ratio<1>>
inline InteractiveMarkerClient(NodePtr node, std::shared_ptr<tf2::BufferCoreInterface> tf_buffer_core, const std::string &target_frame = "", const std::string &topic_namespace = "", const std::chrono::duration<Rep, Period> &request_timeout = std::chrono::seconds(1), const rclcpp::QoS &update_sub_qos = rclcpp::QoS(100), const rclcpp::QoS &feedback_pub_qos = rclcpp::QoS(100))

Constructor.

Parameters:
  • node – The object from which to get the desired node interfaces.

  • tf_buffer_core – The tf transformer to use.

  • target_frame – The tf frame to transform timestamped messages into.

  • topic_namespace – The interactive marker topic namespace. This is the namespace used for the underlying ROS service and topics for communication between the client and server. If the namespace is not empty, then connect() is called.

  • request_timeout – Timeout in seconds before retrying to request interactive markers from a connected server.

  • update_sub_qos – QoS settings for the underlying update subscription.

  • feedback_pub_qos – QoS settings for the underlying feedback publisher.

INTERACTIVE_MARKERS_PUBLIC ~InteractiveMarkerClient()

Destructor.

Calls reset().

INTERACTIVE_MARKERS_PUBLIC void connect (const std::string &topic_namespace)

Connect to a server in a given namespace.

INTERACTIVE_MARKERS_PUBLIC void disconnect ()

Disconnect from a server and clear the update queue.

INTERACTIVE_MARKERS_PUBLIC void update ()

Update the internal state and call registered callbacks.

INTERACTIVE_MARKERS_PUBLIC void publishFeedback (visualization_msgs::msg::InteractiveMarkerFeedback feedback)

Publish a feedback message to the server.

INTERACTIVE_MARKERS_PUBLIC void setTargetFrame (const std::string &target_frame)

Change the target frame.

This resets the connection.

INTERACTIVE_MARKERS_PUBLIC void setInitializeCallback (const InitializeCallback &cb)

Set the initialization callback.

The registered function is called when the client successfully initializes with a connected server.

INTERACTIVE_MARKERS_PUBLIC void setUpdateCallback (const UpdateCallback &cb)

Set the callback for update messages.

If the client is connected and initialized, the registered function is called whenever an update message is received.

INTERACTIVE_MARKERS_PUBLIC void setResetCallback (const ResetCallback &cb)

Set the reset callback.

The registered function is called whenver the connection is reset.

INTERACTIVE_MARKERS_PUBLIC void setStatusCallback (const StatusCallback &cb)

Set the callback for status updates.

The registered function is called whenever there is a status message.

inline INTERACTIVE_MARKERS_PUBLIC void setEnableAutocompleteTransparency (bool enable)
inline INTERACTIVE_MARKERS_PUBLIC State getState () const