#include <Visualizer.h>
|  | 
| bool | getAttributeSettings (ros::NodeHandle &n, const std::string &ns) | 
|  | 
| const pbl::Gaussian * | getBestGaussian (const pbl::PDF &pdf, double min_weight=0) | 
|  | 
| bool | getMarkerParameters (ros::NodeHandle &n, const std::string &ns) | 
|  | 
| void | getStructValue (XmlRpc::XmlRpcValue &s, const std::string &name, float &f, float default_value) | 
|  | 
| void | getStructValue (XmlRpc::XmlRpcValue &s, const std::string &name, double &d, double default_value) | 
|  | 
| void | getStructValue (XmlRpc::XmlRpcValue &s, const std::string &name, bool &b, bool default_value) | 
|  | 
| void | getStructValue (XmlRpc::XmlRpcValue &s, const std::string &name, std::string &str, const std::string &default_value) | 
|  | 
| void | setMarkerType (XmlRpc::XmlRpcValue &v, MarkerInfo &m) | 
|  | 
Definition at line 36 of file Visualizer.h.
 
      
        
          | Visualizer::Visualizer | ( |  | ) |  | 
      
 
 
  
  | 
        
          | Visualizer::~Visualizer | ( |  | ) |  |  | virtual | 
 
 
      
        
          | bool Visualizer::createMarkers | ( | const std_msgs::Header & | header, | 
        
          |  |  | long | ID, | 
        
          |  |  | const std::vector< wire_msgs::Property > & | props, | 
        
          |  |  | std::vector< visualization_msgs::Marker > & | markers_out, | 
        
          |  |  | const std::string & | frame_id | 
        
          |  | ) |  |  | 
      
 
 
  
  | 
        
          | bool Visualizer::getAttributeSettings | ( | ros::NodeHandle & | n, |  
          |  |  | const std::string & | ns |  
          |  | ) |  |  |  | protected | 
 
 
  
  | 
        
          | bool Visualizer::getMarkerParameters | ( | ros::NodeHandle & | n, |  
          |  |  | const std::string & | ns |  
          |  | ) |  |  |  | protected | 
 
 
  
  | 
        
          | void Visualizer::getStructValue | ( | XmlRpc::XmlRpcValue & | s, |  
          |  |  | const std::string & | name, |  
          |  |  | float & | f, |  
          |  |  | float | default_value |  
          |  | ) |  |  |  | protected | 
 
 
  
  | 
        
          | void Visualizer::getStructValue | ( | XmlRpc::XmlRpcValue & | s, |  
          |  |  | const std::string & | name, |  
          |  |  | double & | d, |  
          |  |  | double | default_value |  
          |  | ) |  |  |  | protected | 
 
 
  
  | 
        
          | void Visualizer::getStructValue | ( | XmlRpc::XmlRpcValue & | s, |  
          |  |  | const std::string & | name, |  
          |  |  | bool & | b, |  
          |  |  | bool | default_value |  
          |  | ) |  |  |  | protected | 
 
 
  
  | 
        
          | void Visualizer::getStructValue | ( | XmlRpc::XmlRpcValue & | s, |  
          |  |  | const std::string & | name, |  
          |  |  | std::string & | str, |  
          |  |  | const std::string & | default_value |  
          |  | ) |  |  |  | protected | 
 
 
      
        
          | bool Visualizer::setParameters | ( | ros::NodeHandle & | n, | 
        
          |  |  | const std::string & | ns | 
        
          |  | ) |  |  | 
      
 
 
  
  | 
        
          | std::map<std::string, bool> Visualizer::attribute_map_ |  | protected | 
 
 
  
  | 
        
          | std::map<std::string, Color> Visualizer::color_mapping_ |  | protected | 
 
 
  
  | 
        
          | std::map<std::string, MarkerInfo> Visualizer::object_class_to_marker_map_ |  | protected | 
 
 
The documentation for this class was generated from the following files: