40 QString::fromStdString(ros::message_traits::datatype<visualization_msgs::MarkerArray>()));
45 " This should generally be at least a few times larger than the " 46 "number of Markers in each MarkerArray.");
RosTopicProperty * marker_topic_property_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
virtual bool setValue(const QVariant &new_value)
Set the new value for this property. Returns true if the new value is different from the old value...
void unsubscribe() override
Overridden from MarkerDisplay. Unsubscribes to the marker array topic.
ros::NodeHandle update_nh_
A NodeHandle whose CallbackQueue is run from the main GUI thread (the "update" thread).
IntProperty * queue_size_property_
virtual void setDescription(const QString &description)
Set the description.
std::string getTopicStd() const
void incomingMarkerArray(const visualization_msgs::MarkerArray::ConstPtr &array)
Process a MarkerArray message.
void setMessageType(const QString &message_type)
void subscribe() override
Overridden from MarkerDisplay. Subscribes to the marker array topic.
ros::Subscriber array_sub_
virtual int getInt() const
Return the internal property value as an integer.
bool isEnabled() const
Return true if this Display is enabled, false if not.
Display for an array of markers. The MarkerDisplay class handles MarkerArray messages. This is just a wrapper to let MarkerArray topics get selected in the topic browser.
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
Displays "markers" sent in by other ROS nodes on the "visualization_marker" topic.
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
Show status level and text. This is thread-safe.