#include <Visualizer.h>
Classes | |
| struct | MarkerInfo | 
Public Member Functions | |
| bool | 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 | setParameters (ros::NodeHandle &n, const std::string &ns) | 
| void | setTFListener (tf::TransformListener *tf_listener) | 
| Visualizer () | |
| virtual | ~Visualizer () | 
Protected Member Functions | |
| 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) | 
Protected Attributes | |
| std::map< std::string, bool > | attribute_map_ | 
| std::map< std::string, Color > | color_mapping_ | 
| std::map< std::string, MarkerInfo > | object_class_to_marker_map_ | 
| tf::TransformListener * | tf_listener_ | 
Definition at line 36 of file Visualizer.h.
Definition at line 13 of file Visualizer.cpp.
| Visualizer::~Visualizer | ( | ) |  [virtual] | 
        
Definition at line 31 of file Visualizer.cpp.
| 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 | ||
| ) | 
Definition at line 38 of file Visualizer.cpp.
| bool Visualizer::getAttributeSettings | ( | ros::NodeHandle & | n, | 
| const std::string & | ns | ||
| ) |  [protected] | 
        
Definition at line 494 of file Visualizer.cpp.
| const pbl::Gaussian * Visualizer::getBestGaussian | ( | const pbl::PDF & | pdf, | 
| double | min_weight = 0  | 
        ||
| ) |  [protected] | 
        
Definition at line 227 of file Visualizer.cpp.
| bool Visualizer::getMarkerParameters | ( | ros::NodeHandle & | n, | 
| const std::string & | ns | ||
| ) |  [protected] | 
        
Definition at line 324 of file Visualizer.cpp.
| void Visualizer::getStructValue | ( | XmlRpc::XmlRpcValue & | s, | 
| const std::string & | name, | ||
| float & | f, | ||
| float | default_value | ||
| ) |  [protected] | 
        
Definition at line 275 of file Visualizer.cpp.
| void Visualizer::getStructValue | ( | XmlRpc::XmlRpcValue & | s, | 
| const std::string & | name, | ||
| double & | d, | ||
| double | default_value | ||
| ) |  [protected] | 
        
Definition at line 256 of file Visualizer.cpp.
| void Visualizer::getStructValue | ( | XmlRpc::XmlRpcValue & | s, | 
| const std::string & | name, | ||
| bool & | b, | ||
| bool | default_value | ||
| ) |  [protected] | 
        
Definition at line 284 of file Visualizer.cpp.
| void Visualizer::getStructValue | ( | XmlRpc::XmlRpcValue & | s, | 
| const std::string & | name, | ||
| std::string & | str, | ||
| const std::string & | default_value | ||
| ) |  [protected] | 
        
| void Visualizer::setMarkerType | ( | XmlRpc::XmlRpcValue & | v, | 
| MarkerInfo & | m | ||
| ) |  [protected] | 
        
Definition at line 454 of file Visualizer.cpp.
| bool Visualizer::setParameters | ( | ros::NodeHandle & | n, | 
| const std::string & | ns | ||
| ) | 
Definition at line 310 of file Visualizer.cpp.
| void Visualizer::setTFListener | ( | tf::TransformListener * | tf_listener | ) | 
Definition at line 220 of file Visualizer.cpp.
std::map<std::string, bool> Visualizer::attribute_map_ [protected] | 
        
Definition at line 74 of file Visualizer.h.
std::map<std::string, Color> Visualizer::color_mapping_ [protected] | 
        
Definition at line 65 of file Visualizer.h.
std::map<std::string, MarkerInfo> Visualizer::object_class_to_marker_map_ [protected] | 
        
Definition at line 71 of file Visualizer.h.
tf::TransformListener* Visualizer::tf_listener_ [protected] | 
        
Definition at line 68 of file Visualizer.h.