Go to the documentation of this file.
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.");
bool isEnabled() const
Return true if this Display is enabled, false if not.
Displays "markers" sent in by other ROS nodes on the "visualization_marker" topic.
ros::Subscriber array_sub_
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
Show status level and text. This is thread-safe.
Display for an array of markers. The MarkerDisplay class handles MarkerArray messages....
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
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.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
std::string getTopicStd() const
virtual void setDescription(const QString &description)
Set the description.
void subscribe() override
Overridden from MarkerDisplay. Subscribes to the marker array topic.
void setMessageType(const QString &message_type)
RosTopicProperty * marker_topic_property_
virtual int getInt() const
Return the internal property value as an integer.
IntProperty * queue_size_property_
void incomingMarkerArray(const visualization_msgs::MarkerArray::ConstPtr &array)
Process a MarkerArray message.
ros::NodeHandle update_nh_
A NodeHandle whose CallbackQueue is run from the main GUI thread (the "update" thread).
rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Fri Aug 2 2024 08:43:09