59                                                  QString::fromStdString( ros::message_traits::datatype<visualization_msgs::Marker>() ),
    60                                                  "visualization_msgs::Marker topic to subscribe to.  <topic>_array will also"    61                                                  " automatically be subscribed with type visualization_msgs::MarkerArray.",
    65                                           "Advanced: set the size of the incoming Marker message queue.  Increasing this is"    66                                           " useful if your incoming TF data is delayed significantly from your Marker data, "    67                                           "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() )
   183   M_IDToMarker::iterator it = 
markers_.find( 
id );
   194   std::vector<MarkerID> to_delete;
   197   M_IDToMarker::iterator marker_it = 
markers_.begin();
   198   M_IDToMarker::iterator marker_end = 
markers_.end();
   199   for (; marker_it != marker_end; ++marker_it)
   201     if (marker_it->first.first == ns)
   203       to_delete.push_back(marker_it->first);
   208     std::vector<MarkerID>::iterator it = to_delete.begin();
   209     std::vector<MarkerID>::iterator end = to_delete.end();
   210     for (; it != end; ++it)
   219   std::vector<MarkerID> to_delete;
   220   M_IDToMarker::iterator marker_it = 
markers_.begin();
   221   for (; marker_it != 
markers_.end(); ++marker_it)
   223     to_delete.push_back(marker_it->first);
   226   for (std::vector<MarkerID>::iterator it = to_delete.begin(); it != to_delete.end(); ++it)
   234   std::stringstream ss;
   235   ss << 
id.first << 
"/" << 
id.second;
   236   std::string marker_name = ss.str();
   242   std::stringstream ss;
   243   ss << 
id.first << 
"/" << 
id.second;
   244   std::string marker_name = ss.str();
   250   std::vector<visualization_msgs::Marker>::const_iterator it = array->markers.begin();
   251   std::vector<visualization_msgs::Marker>::const_iterator end = array->markers.end();
   252   for (; it != end; ++it)
   254     const visualization_msgs::Marker& marker = *it;
   255     tf_filter_->
add(visualization_msgs::Marker::Ptr(
new visualization_msgs::Marker(marker)));
   268   visualization_msgs::Marker::ConstPtr marker = marker_evt.
getConstMessage();
   269   if (marker->action == visualization_msgs::Marker::DELETE ||
   294                      "Contains invalid floating point values (nans or infs)" );
   301                          "This warning will only be output once but may be true for others; "   302                          "enable DEBUG messages for ros.rviz.quaternions to see more details.",
   303                          message->ns.c_str(), message->id );
   304     ROS_DEBUG_NAMED( 
"quaternions", 
"Marker '%s/%d' contains unnormalized quaternions.", 
   305                      message->ns.c_str(), message->id );
   308   switch ( message->action )
   310   case visualization_msgs::Marker::ADD:
   314   case visualization_msgs::Marker::DELETE:
   323     ROS_ERROR( 
"Unknown marker action: %d\n", message->action );
   329   QString namespace_name = QString::fromStdString( message->ns );
   330   M_Namespace::iterator ns_it = 
namespaces_.find( namespace_name );
   339       ns_it.value()->setValue(
false);  
   343   if( !ns_it.value()->isEnabled() )
   353   M_IDToMarker::iterator it = 
markers_.find( 
MarkerID(message->ns, message->id) );
   358     if ( message->type == marker->getMessage()->type )
   372       ROS_ERROR( 
"Unknown marker type: %d", message->type );
   374     markers_.insert(std::make_pair(
MarkerID(message->ns, message->id), marker));
   379     marker->setMessage(message);
   381     if (message->lifetime.toSec() > 0.0001f)
   386     if (message->frame_locked)
   412   if ( !local_queue.empty() )
   414     V_MarkerMessage::iterator message_it = local_queue.begin();
   415     V_MarkerMessage::iterator message_end = local_queue.end();
   416     for ( ; message_it != message_end; ++message_it )
   418       visualization_msgs::Marker::ConstPtr& marker = *message_it;
   430       if (marker->expired())
   445     for (; it != end; ++it)
   448       marker->updateFrameLocked();
   476                   "Enable/disable all markers in this namespace.",
 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...
void processMessage(const visualization_msgs::Marker::ConstPtr &message)
Processes a marker message. 
void deleteStatusStd(const std::string &name)
Delete the status entry with the given std::string name. This is thread-safe. 
virtual void update(float wall_dt, float ros_dt)
Called periodically by the visualization manager. 
virtual void setString(const QString &str)
void processAdd(const visualization_msgs::Marker::ConstPtr &message)
Processes an "Add" marker message. 
std::string discoverFailureReason(const std::string &frame_id, const ros::Time &stamp, const std::string &caller_id, tf::FilterFailureReason reason)
Create a description of a transform problem. 
void processDelete(const visualization_msgs::Marker::ConstPtr &message)
Processes a "Delete" marker message. 
S_MarkerBase frame_locked_markers_
void setMarkerStatus(MarkerID id, StatusLevel level, const std::string &text)
RosTopicProperty * marker_topic_property_
virtual tf::TransformListener * getTFClient() const =0
Convenience function: returns getFrameManager()->getTFClient(). 
MarkerNamespace(const QString &name, Property *parent_property, MarkerDisplay *owner)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
DisplayContext * context_
This DisplayContext pointer is the main connection a Display has into the rest of rviz...
void changed()
Emitted by setValue() just after the value has changed. 
void add(const MEvent &evt)
std::vector< visualization_msgs::Marker::ConstPtr > V_MarkerMessage
virtual int getInt() const 
Return the internal property value as an integer. 
ros::NodeHandle update_nh_
A NodeHandle whose CallbackQueue is run from the main GUI thread (the "update" thread). 
A single element of a property tree, with a name, value, description, and possibly children...
IntProperty * queue_size_property_
boost::mutex queue_mutex_
virtual void reset()
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. 
bool isValid()
Return true if the iterator currently points to a valid entry, false if not. 
virtual void unsubscribe()
Unsubscribes from the "visualization_marker" "visualization_marker_array" topics. ...
Property specialized to provide max/min enforcement for integers. 
Ogre::SceneNode * scene_node_
The Ogre::SceneNode to hold all 3D scene elements shown by this Display. 
M_EnabledState namespace_config_enabled_state_
void deleteMarker(MarkerID id)
bool isEnabled() const 
Return true if this Display is enabled, false if not. 
Configuration data storage class. 
Property * namespaces_category_
void incomingMarkerArray(const visualization_msgs::MarkerArray::ConstPtr &array)
Process a MarkerArray message. 
QString fixed_frame_
A convenience variable equal to context_->getFixedFrame(). 
virtual void setQueueSize(uint32_t new_queue_size)
const std::string & getPublisherName() const 
MarkerBase * createMarker(int marker_type, MarkerDisplay *owner, DisplayContext *context, Ogre::SceneNode *parent_node)
void deleteMarkersInNamespace(const std::string &ns)
Delete all the markers within the given namespace. 
std::pair< std::string, int32_t > MarkerID
#define ROS_DEBUG_NAMED(name,...)
const boost::shared_ptr< ConstMessage > & getConstMessage() const 
M_IDToMarker markers_
Map of marker id to the marker info structure. 
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...
bool validateFloats(const sensor_msgs::CameraInfo &msg)
virtual void reset()
Called to tell the display to clear its state. 
V_MarkerMessage message_queue_
virtual void load(const Config &config)
Load the settings for this display from the given Config node, which must be a map. 
virtual void onDisable()
Derived classes override this to do the actual work of disabling themselves. 
QVariant getValue() const 
If this config object is valid and is a Value type, this returns its value. Otherwise it returns an i...
void deleteMarkerStatus(MarkerID id)
virtual void fixedFrameChanged()
Called by setFixedFrame(). Override to respond to changes to fixed_frame_. 
Iterator class for looping over all entries in a Map type Config Node. 
message_filters::Connection registerFailureCallback(const FailureCallback &callback)
virtual FrameManager * getFrameManager() const =0
Return the FrameManager instance. 
ros::Subscriber array_sub_
message_filters::Subscriber< visualization_msgs::Marker > sub_
#define ROS_WARN_ONCE_NAMED(name,...)
friend class MarkerNamespace
tf::MessageFilter< visualization_msgs::Marker > * tf_filter_
void failedMarker(const ros::MessageEvent< visualization_msgs::Marker > &marker_evt, tf::FilterFailureReason reason)
S_MarkerBase markers_with_expiration_
virtual void subscribe()
Subscribes to the "visualization_marker" and "visualization_marker_array" topics. ...
virtual void queueRender()=0
Queues a render. Multiple calls before a render happens will only cause a single render. 
virtual void load(const Config &config)
Load the settings for this display from the given Config node, which must be a map. 
virtual void onEnable()
Derived classes override this to do the actual work of enabling themselves. 
MapIterator mapIterator() const 
Return a new iterator for looping over key/value pairs. 
virtual void setTopic(const QString &topic, const QString &datatype)
Set the ROS topic to listen to for this display. 
void deleteAllMarkers()
Delete all known markers to this plugin, regardless of id or namespace. 
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
Property(const QString &name=QString(), const QVariant default_value=QVariant(), const QString &description=QString(), Property *parent=0, const char *changed_slot=0, QObject *receiver=0)
Constructor. 
bool validateQuaternions(const visualization_msgs::InteractiveMarker &marker)
Property specialized to provide getter for booleans. 
void setTargetFrame(const std::string &target_frame)
Config mapGetChild(const QString &key) const 
If the referenced Node is a Map and it has a child with the given key, return a reference to the chil...
bool initialized() const 
Returns true if the display has been initialized. 
std::string getTopicStd() const 
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
Displays "markers" sent in by other ROS nodes on the "visualization_marker" topic. 
void clearMarkers()
Removes all the markers. 
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
Show status level and text. This is thread-safe. 
virtual QString getName() const 
Return the name of this Property as a QString. 
Connection registerCallback(const C &callback)
virtual void onInitialize()
Override this function to do subclass-specific initialization.