18 #ifndef MARKER_HELPER_H 19 #define MARKER_HELPER_H 22 #include <visualization_msgs/MarkerArray.h> 38 bool parseDoubleCsv(std::string csv_in, std::vector<double> &csv_out, std::string delim);
40 visualization_msgs::Marker
createMarker(
const std::string &name,
const std::string &mesh,
const std::vector<double> &pose,
const std::vector<double> &scale,
int id,
bool use_mat);
42 visualization_msgs::MarkerArray
parseXmlFile(std::string xml_path);
48 MarkerHelper(
double marker_lifetime,
const std::string &dome_config_path,
const std::string &mild_config_path);
std::string dome_config_path_
visualization_msgs::MarkerArray getAllMarkersMild()
visualization_msgs::Marker createMarker(const std::string &name, const std::string &mesh, const std::vector< double > &pose, const std::vector< double > &scale, int id, bool use_mat)
double DEFAULT_MARKER_LIFETIME
visualization_msgs::MarkerArray getAllMarkersDome()
std::string mild_config_path_
bool parseDoubleCsv(std::string csv_in, std::vector< double > &csv_out, std::string delim)
visualization_msgs::MarkerArray parseXmlFile(std::string xml_path)