Go to the documentation of this file.
55 "Marker Topic",
"visualization_marker",
56 QString::fromStdString(ros::message_traits::datatype<visualization_msgs::Marker>()),
57 "visualization_msgs::Marker topic to subscribe to. <topic>_array will also"
58 " automatically be subscribed with type visualization_msgs::MarkerArray.",
63 "Advanced: set the size of the incoming Marker message queue. Increasing this is"
64 " useful if your incoming TF data is delayed significantly from your Marker data, "
65 "but it can greatly increase memory usage if the messages are big.",
107 QString key = iter.currentKey();
108 const Config& child = iter.currentChild();
155 if (!marker_topic.empty())
188 M_IDToMarker::iterator it =
markers_.find(
id);
199 std::vector<MarkerID> to_delete;
202 M_IDToMarker::iterator marker_it =
markers_.begin();
203 M_IDToMarker::iterator marker_end =
markers_.end();
204 for (; marker_it != marker_end; ++marker_it)
206 if (marker_it->first.first == ns)
208 to_delete.push_back(marker_it->first);
213 std::vector<MarkerID>::iterator it = to_delete.begin();
214 std::vector<MarkerID>::iterator end = to_delete.end();
215 for (; it != end; ++it)
224 std::vector<MarkerID> to_delete;
225 M_IDToMarker::iterator marker_it =
markers_.begin();
226 for (; marker_it !=
markers_.end(); ++marker_it)
228 to_delete.push_back(marker_it->first);
231 for (std::vector<MarkerID>::iterator it = to_delete.begin(); it != to_delete.end(); ++it)
239 std::stringstream ss;
240 ss <<
id.first <<
"/" <<
id.second;
241 std::string marker_name = ss.str();
247 std::stringstream ss;
248 ss <<
id.first <<
"/" <<
id.second;
249 std::string marker_name = ss.str();
256 for (
const visualization_msgs::Marker& marker : array->markers)
258 tf_filter_->
add(visualization_msgs::Marker::Ptr(
new visualization_msgs::Marker(marker)));
271 const visualization_msgs::Marker::ConstPtr& marker = marker_evt.
getConstMessage();
272 if (marker->action == visualization_msgs::Marker::DELETE ||
273 marker->action == visualization_msgs::Marker::DELETEALL)
279 marker->header.frame_id, marker->header.stamp, authority, reason);
286 switch (message->action)
288 case visualization_msgs::Marker::ADD:
296 case visualization_msgs::Marker::DELETE:
300 case visualization_msgs::Marker::DELETEALL:
305 ROS_ERROR(
"Unknown marker action: %d\n", message->action);
311 QString namespace_name = QString::fromStdString(message->ns);
312 M_Namespace::iterator ns_it =
namespaces_.find(namespace_name);
322 ns_it.value()->setValue(
false);
326 if (!ns_it.value()->isEnabled())
334 M_IDToMarker::iterator it =
markers_.find(
MarkerID(message->ns, message->id));
339 if (message->type == marker->getMessage()->type)
354 markers_.insert(std::make_pair(
MarkerID(message->ns, message->id), marker));
360 marker->setMessage(message);
362 if (message->lifetime.toSec() > 0.0001f)
367 if (message->frame_locked)
393 if (!local_queue.empty())
395 V_MarkerMessage::iterator message_it = local_queue.begin();
396 V_MarkerMessage::iterator message_end = local_queue.end();
397 for (; message_it != message_end; ++message_it)
399 visualization_msgs::Marker::ConstPtr& marker = *message_it;
411 if (marker->expired())
426 for (; it != end; ++it)
429 marker->updateFrameLocked();
456 :
BoolProperty(name, true,
"Enable/disable all markers in this namespace.", parent_property)
void onDisable() override
Derived classes override this to do the actual work of disabling themselves.
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.
message_filters::Connection registerFailureCallback(const FailureCallback &callback)
virtual void queueRender()=0
Queues a render. Multiple calls before a render happens will only cause a single render.
bool initialized() const
Returns true if the display has been initialized.
bool isValid()
Return true if the iterator currently points to a valid entry, false if not.
message_filters::Subscriber< visualization_msgs::Marker > sub_
void update(float wall_dt, float ros_dt) override
Called periodically by the visualization manager.
void processAdd(const visualization_msgs::Marker::ConstPtr &message)
Processes an "Add" marker message.
void reset() override
Called to tell the display to clear its state.
void incomingMarker(const visualization_msgs::Marker::ConstPtr &marker)
ROS callback notifying us of a new marker.
MarkerBase * createMarker(int marker_type, MarkerDisplay *owner, DisplayContext *context, Ogre::SceneNode *parent_node)
void onEnable() override
Derived classes override this to do the actual work of enabling themselves.
Property specialized to provide getter for booleans.
virtual void setString(const QString &str)
V_MarkerMessage message_queue_
in our update() function
const std::string & getPublisherName() const
ros::Subscriber array_sub_
Property * namespaces_category_
QString fixed_frame_
A convenience variable equal to context_->getFixedFrame().
MarkerNamespace(const QString &name, Property *parent_property, MarkerDisplay *owner)
const boost::shared_ptr< ConstMessage > & getConstMessage() const
std::vector< visualization_msgs::Marker::ConstPtr > V_MarkerMessage
Property(const QString &name=QString(), const QVariant &default_value=QVariant(), const QString &description=QString(), Property *parent=nullptr)
Constructor.
void setTopic(const QString &topic, const QString &datatype) override
Set the ROS topic to listen to for this display.
void deleteStatusStd(const std::string &name)
Delete the status entry with the given std::string name. This is thread-safe.
boost::mutex queue_mutex_
QMetaObject::Connection connect(const QObject *receiver, const char *slot, Qt::ConnectionType type=Qt::AutoConnection)
Connect changed() signal to given slot of receiver.
A single element of a property tree, with a name, value, description, and possibly children.
void processMessage(const visualization_msgs::Marker::ConstPtr &message)
Processes a marker message.
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
Show status level and text. This is thread-safe.
void deleteMarker(const MarkerID &id)
void deleteMarkerInternal(const MarkerID &id)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
void load(const Config &config) override
Load the value of this property and/or its children from the given Config reference.
Ogre::SceneNode * scene_node_
The Ogre::SceneNode to hold all 3D scene elements shown by this Display.
~MarkerDisplay() override
M_EnabledState namespace_config_enabled_state_
tf2_ros::MessageFilter< visualization_msgs::Marker > * tf_filter_
void deleteMarkerStatus(const MarkerID &id)
void load(const Config &config) override
Load the settings for this display from the given Config node, which must be a map.
bool checkMarkerMsg(const visualization_msgs::Marker &marker, MarkerDisplay *owner)
virtual void unsubscribe()
Unsubscribes from the "visualization_marker" "visualization_marker_array" topics.
void setTargetFrame(const std::string &target_frame)
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())
virtual FrameManager * getFrameManager() const =0
Return the FrameManager instance.
virtual void setQueueSize(uint32_t new_queue_size)
std::string getTopicStd() const
void deleteAllMarkers()
Delete all known markers to this plugin, regardless of id or namespace.
virtual QString getName() const
Return the name of this Property as a QString.
void setStatusStd(StatusProperty::Level level, const std::string &name, const std::string &text)
Show status level and text, using a std::string. Convenience function which converts std::string to Q...
DisplayContext * context_
This DisplayContext pointer is the main connection a Display has into the rest of rviz....
M_IDToMarker markers_
Map of marker id to the marker info structure.
std::pair< std::string, int32_t > MarkerID
bool checkMarkerArrayMsg(const visualization_msgs::MarkerArray &array, MarkerDisplay *owner)
void clearMarkers()
Removes all the markers.
virtual void subscribe()
Subscribes to the "visualization_marker" and "visualization_marker_array" topics.
S_MarkerBase frame_locked_markers_
RosTopicProperty * marker_topic_property_
void onInitialize() override
Override this function to do subclass-specific initialization.
void add(const MConstPtr &message)
void changed()
Emitted by setValue() just after the value has changed.
virtual void reset()
Called to tell the display to clear its state.
virtual int getInt() const
Return the internal property value as an integer.
void processDelete(const visualization_msgs::Marker::ConstPtr &message)
Processes a "Delete" marker message.
S_MarkerBase markers_with_expiration_
void failedMarker(const ros::MessageEvent< visualization_msgs::Marker > &marker_evt, tf2_ros::FilterFailureReason reason)
IntProperty * queue_size_property_
Iterator class for looping over all entries in a Map type Config Node.
void incomingMarkerArray(const visualization_msgs::MarkerArray::ConstPtr &array)
Process a MarkerArray message.
virtual void removeChildren(int start_index=0, int count=-1)
Remove and delete some or all child Properties. Does not change the value of this Property.
void deleteMarkersInNamespace(const std::string &ns)
Delete all the markers within the given namespace.
MapIterator mapIterator() const
Return a new iterator for looping over key/value pairs.
void fixedFrameChanged() override
Called by setFixedFrame(). Override to respond to changes to fixed_frame_.
std::shared_ptr< tf2_ros::Buffer > getTF2BufferPtr() const
Convenience function: returns getFrameManager()->getTF2BufferPtr().
Configuration data storage class.
friend class MarkerNamespace
ros::NodeHandle update_nh_
A NodeHandle whose CallbackQueue is run from the main GUI thread (the "update" thread).
QVariant getValue() const
If this config object is valid and is a Value type, this returns its value. Otherwise it returns an i...
std::string discoverFailureReason(const std::string &frame_id, const ros::Time &stamp, const std::string &caller_id, tf2_ros::FilterFailureReason reason)
Property specialized to provide max/min enforcement for integers.
void setMarkerStatus(const MarkerID &id, StatusLevel level, const std::string &text)
rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Fri Aug 2 2024 08:43:09