$search

Visualizer Class Reference

#include <Visualizer.h>

List of all members.

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::GaussiangetBestGaussian (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, std::string &str, const std::string &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, double &d, double default_value)
void getStructValue (XmlRpc::XmlRpcValue &s, const std::string &name, float &f, float default_value)
void setMarkerType (XmlRpc::XmlRpcValue &v, MarkerInfo &m)

Protected Attributes

std::map< std::string, bool > attribute_map_
std::map< std::string, Colorcolor_mapping_
std::map< std::string, MarkerInfoobject_class_to_marker_map_
tf::TransformListenertf_listener_

Detailed Description

Definition at line 36 of file Visualizer.h.


Constructor & Destructor Documentation

Visualizer::Visualizer (  ) 

Definition at line 13 of file Visualizer.cpp.

Visualizer::~Visualizer (  )  [virtual]

Definition at line 31 of file Visualizer.cpp.


Member Function Documentation

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]
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]
void Visualizer::getStructValue ( XmlRpc::XmlRpcValue s,
const std::string &  name,
std::string &  str,
const std::string &  default_value 
) [protected]
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,
double &  d,
double  default_value 
) [protected]

Definition at line 256 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::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 
)
void Visualizer::setTFListener ( tf::TransformListener tf_listener  ) 

Definition at line 220 of file Visualizer.cpp.


Member Data Documentation

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.

Definition at line 68 of file Visualizer.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


wire_viz
Author(s): Jos Elfring, Sjoerd van den Dries
autogenerated on Tue Mar 5 12:29:01 2013